diff --git a/src/ICM_20948.cpp b/src/ICM_20948.cpp new file mode 100644 index 0000000..a73f23a --- /dev/null +++ b/src/ICM_20948.cpp @@ -0,0 +1,2089 @@ +#include "ICM_20948.h" + +#include "util/ICM_20948_REGISTERS.h" +#include "util/AK09916_REGISTERS.h" + +// Forward Declarations +ICM_20948_Status_e ICM_20948_write_I2C(uint8_t reg, uint8_t *data, uint32_t len, void *user); +ICM_20948_Status_e ICM_20948_read_I2C(uint8_t reg, uint8_t *buff, uint32_t len, void *user); +ICM_20948_Status_e ICM_20948_write_SPI(uint8_t reg, uint8_t *buff, uint32_t len, void *user); +ICM_20948_Status_e ICM_20948_read_SPI(uint8_t reg, uint8_t *buff, uint32_t len, void *user); + +// Base +ICM_20948::ICM_20948() +{ + status = ICM_20948_init_struct(&_device); +} + +void ICM_20948::enableDebugging(Stream &debugPort) +{ + _debugSerial = &debugPort; //Grab which port the user wants us to use for debugging + _printDebug = true; //Should we print the commands we send? Good for debugging +} +void ICM_20948::disableDebugging(void) +{ + _printDebug = false; //Turn off extra print statements +} + +// Debug Printing: based on gfvalvo's flash string helper code: +// https://forum.arduino.cc/index.php?topic=533118.msg3634809#msg3634809 + +void ICM_20948::debugPrint(const char *line) +{ + doDebugPrint([](const char *ptr) { return *ptr; }, line); +} + +void ICM_20948::debugPrint(const __FlashStringHelper *line) +{ + doDebugPrint([](const char *ptr) { return (char)pgm_read_byte_near(ptr); }, + (const char *)line); +} + +void ICM_20948::debugPrintln(const char *line) +{ + doDebugPrint([](const char *ptr) { return *ptr; }, line, true); +} + +void ICM_20948::debugPrintln(const __FlashStringHelper *line) +{ + doDebugPrint([](const char *ptr) { return (char)pgm_read_byte_near(ptr); }, + (const char *)line, true); +} + +void ICM_20948::doDebugPrint(char (*funct)(const char *), const char *string, bool newLine) +{ + if (_printDebug == false) + return; // Bail if debugging is not enabled + + char ch; + + while ((ch = funct(string++))) + { + _debugSerial->print(ch); + } + + if (newLine) + { + _debugSerial->println(); + } +} + +void ICM_20948::debugPrintf(int i) +{ + if (_printDebug == true) + _debugSerial->print(i); +} + +void ICM_20948::debugPrintf(float f) +{ + if (_printDebug == true) + _debugSerial->print(f); +} + +void ICM_20948::debugPrintStatus(ICM_20948_Status_e stat) +{ + switch (stat) + { + case ICM_20948_Stat_Ok: + debugPrint(F("All is well.")); + break; + case ICM_20948_Stat_Err: + debugPrint(F("General Error")); + break; + case ICM_20948_Stat_NotImpl: + debugPrint(F("Not Implemented")); + break; + case ICM_20948_Stat_ParamErr: + debugPrint(F("Parameter Error")); + break; + case ICM_20948_Stat_WrongID: + debugPrint(F("Wrong ID")); + break; + case ICM_20948_Stat_InvalSensor: + debugPrint(F("Invalid Sensor")); + break; + case ICM_20948_Stat_NoData: + debugPrint(F("Data Underflow")); + break; + case ICM_20948_Stat_SensorNotSupported: + debugPrint(F("Sensor Not Supported")); + break; + case ICM_20948_Stat_DMPNotSupported: + debugPrint(F("DMP Firmware Not Supported. Is #define ICM_20948_USE_DMP commented in util/ICM_20948_C.h?")); + break; + case ICM_20948_Stat_DMPVerifyFail: + debugPrint(F("DMP Firmware Verification Failed")); + break; + case ICM_20948_Stat_FIFONoDataAvail: + debugPrint(F("No FIFO Data Available")); + break; + case ICM_20948_Stat_FIFOIncompleteData: + debugPrint(F("DMP data in FIFO was incomplete")); + break; + case ICM_20948_Stat_FIFOMoreDataAvail: + debugPrint(F("More FIFO Data Available")); + break; + case ICM_20948_Stat_UnrecognisedDMPHeader: + debugPrint(F("Unrecognised DMP Header")); + break; + case ICM_20948_Stat_UnrecognisedDMPHeader2: + debugPrint(F("Unrecognised DMP Header2")); + break; + case ICM_20948_Stat_InvalDMPRegister: + debugPrint(F("Invalid DMP Register")); + break; + default: + debugPrint(F("Unknown Status")); + break; + } +} + +ICM_20948_AGMT_t ICM_20948::getAGMT(void) +{ + status = ICM_20948_get_agmt(&_device, &agmt); + + return agmt; +} + +float ICM_20948::magX(void) +{ + return getMagUT(agmt.mag.axes.x); +} + +float ICM_20948::magY(void) +{ + return getMagUT(agmt.mag.axes.y); +} + +float ICM_20948::magZ(void) +{ + return getMagUT(agmt.mag.axes.z); +} + +float ICM_20948::getMagUT(int16_t axis_val) +{ + return (((float)axis_val) * 0.15); +} + +float ICM_20948::accX(void) +{ + return getAccMG(agmt.acc.axes.x); +} + +float ICM_20948::accY(void) +{ + return getAccMG(agmt.acc.axes.y); +} + +float ICM_20948::accZ(void) +{ + return getAccMG(agmt.acc.axes.z); +} + +float ICM_20948::getAccMG(int16_t axis_val) +{ + switch (agmt.fss.a) + { + case 0: + return (((float)axis_val) / 16.384); + break; + case 1: + return (((float)axis_val) / 8.192); + break; + case 2: + return (((float)axis_val) / 4.096); + break; + case 3: + return (((float)axis_val) / 2.048); + break; + default: + return 0; + break; + } +} + +float ICM_20948::gyrX(void) +{ + return getGyrDPS(agmt.gyr.axes.x); +} + +float ICM_20948::gyrY(void) +{ + return getGyrDPS(agmt.gyr.axes.y); +} + +float ICM_20948::gyrZ(void) +{ + return getGyrDPS(agmt.gyr.axes.z); +} + +float ICM_20948::getGyrDPS(int16_t axis_val) +{ + switch (agmt.fss.g) + { + case 0: + return (((float)axis_val) / 131); + break; + case 1: + return (((float)axis_val) / 65.5); + break; + case 2: + return (((float)axis_val) / 32.8); + break; + case 3: + return (((float)axis_val) / 16.4); + break; + default: + return 0; + break; + } +} + +//Gyro Bias +ICM_20948_Status_e ICM_20948::setBiasGyroX( int32_t newValue) +{ + if (_device._dmp_firmware_available == true) // Is DMP supported? + { + unsigned char gyro_bias_reg[4]; + gyro_bias_reg[0] = (unsigned char)(newValue >> 24); + gyro_bias_reg[1] = (unsigned char)(newValue >> 16); + gyro_bias_reg[2] = (unsigned char)(newValue >> 8); + gyro_bias_reg[3] = (unsigned char)(newValue & 0xff); + status = inv_icm20948_write_mems(&_device, GYRO_BIAS_X, 4, (const unsigned char*)&gyro_bias_reg); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::setBiasGyroY( int32_t newValue) +{ + if (_device._dmp_firmware_available == true) // Is DMP supported? + { + unsigned char gyro_bias_reg[4]; + gyro_bias_reg[0] = (unsigned char)(newValue >> 24); + gyro_bias_reg[1] = (unsigned char)(newValue >> 16); + gyro_bias_reg[2] = (unsigned char)(newValue >> 8); + gyro_bias_reg[3] = (unsigned char)(newValue & 0xff); + status = inv_icm20948_write_mems(&_device, GYRO_BIAS_Y, 4, (const unsigned char*)&gyro_bias_reg); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::setBiasGyroZ( int32_t newValue) +{ + if (_device._dmp_firmware_available == true) // Is DMP supported? + { + unsigned char gyro_bias_reg[4]; + gyro_bias_reg[0] = (unsigned char)(newValue >> 24); + gyro_bias_reg[1] = (unsigned char)(newValue >> 16); + gyro_bias_reg[2] = (unsigned char)(newValue >> 8); + gyro_bias_reg[3] = (unsigned char)(newValue & 0xff); + status = inv_icm20948_write_mems(&_device, GYRO_BIAS_Z, 4, (const unsigned char*)&gyro_bias_reg); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::getBiasGyroX( int32_t* bias) +{ + if (_device._dmp_firmware_available == true) // Is DMP supported? + { + unsigned char bias_data[4] = { 0 }; + status = inv_icm20948_read_mems(&_device, GYRO_BIAS_X, 4, bias_data); + union { + int32_t signed32; + uint32_t unsigned32; + } signedUnsigned32; + signedUnsigned32.unsigned32 = (((uint32_t)bias_data[0]) << 24) | (((uint32_t)bias_data[1]) << 16) | (((uint32_t)bias_data[2]) << 8) | (bias_data[3]); + *bias = signedUnsigned32.signed32; // Convert from unsigned to signed with no cast ambiguity + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::getBiasGyroY( int32_t* bias) +{ + if (_device._dmp_firmware_available == true) // Is DMP supported? + { + unsigned char bias_data[4] = { 0 }; + status = inv_icm20948_read_mems(&_device, GYRO_BIAS_Y, 4, bias_data); + union { + int32_t signed32; + uint32_t unsigned32; + } signedUnsigned32; + signedUnsigned32.unsigned32 = (((uint32_t)bias_data[0]) << 24) | (((uint32_t)bias_data[1]) << 16) | (((uint32_t)bias_data[2]) << 8) | (bias_data[3]); + *bias = signedUnsigned32.signed32; // Convert from unsigned to signed with no cast ambiguity + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::getBiasGyroZ( int32_t* bias) +{ + if (_device._dmp_firmware_available == true) // Is DMP supported? + { + unsigned char bias_data[4] = { 0 }; + status = inv_icm20948_read_mems(&_device, GYRO_BIAS_Z, 4, bias_data); + union { + int32_t signed32; + uint32_t unsigned32; + } signedUnsigned32; + signedUnsigned32.unsigned32 = (((uint32_t)bias_data[0]) << 24) | (((uint32_t)bias_data[1]) << 16) | (((uint32_t)bias_data[2]) << 8) | (bias_data[3]); + *bias = signedUnsigned32.signed32; // Convert from unsigned to signed with no cast ambiguity + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} +//Accel Bias +ICM_20948_Status_e ICM_20948::setBiasAccelX( int32_t newValue) +{ + if (_device._dmp_firmware_available == true) // Is DMP supported? + { + unsigned char accel_bias_reg[4]; + accel_bias_reg[0] = (unsigned char)(newValue >> 24); + accel_bias_reg[1] = (unsigned char)(newValue >> 16); + accel_bias_reg[2] = (unsigned char)(newValue >> 8); + accel_bias_reg[3] = (unsigned char)(newValue & 0xff); + status = inv_icm20948_write_mems(&_device, ACCEL_BIAS_X, 4, (const unsigned char*)&accel_bias_reg); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::setBiasAccelY( int32_t newValue) +{ + if (_device._dmp_firmware_available == true) // Is DMP supported? + { + unsigned char accel_bias_reg[4]; + accel_bias_reg[0] = (unsigned char)(newValue >> 24); + accel_bias_reg[1] = (unsigned char)(newValue >> 16); + accel_bias_reg[2] = (unsigned char)(newValue >> 8); + accel_bias_reg[3] = (unsigned char)(newValue & 0xff); + status = inv_icm20948_write_mems(&_device, ACCEL_BIAS_Y, 4, (const unsigned char*)&accel_bias_reg); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::setBiasAccelZ( int32_t newValue) +{ + if (_device._dmp_firmware_available == true) // Is DMP supported? + { + unsigned char accel_bias_reg[4]; + accel_bias_reg[0] = (unsigned char)(newValue >> 24); + accel_bias_reg[1] = (unsigned char)(newValue >> 16); + accel_bias_reg[2] = (unsigned char)(newValue >> 8); + accel_bias_reg[3] = (unsigned char)(newValue & 0xff); + status = inv_icm20948_write_mems(&_device, ACCEL_BIAS_Z, 4, (const unsigned char*)&accel_bias_reg); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::getBiasAccelX( int32_t* bias) +{ + if (_device._dmp_firmware_available == true) // Is DMP supported? + { + unsigned char bias_data[4] = { 0 }; + status = inv_icm20948_read_mems(&_device, ACCEL_BIAS_X, 4, bias_data); + union { + int32_t signed32; + uint32_t unsigned32; + } signedUnsigned32; + signedUnsigned32.unsigned32 = (((uint32_t)bias_data[0]) << 24) | (((uint32_t)bias_data[1]) << 16) | (((uint32_t)bias_data[2]) << 8) | (bias_data[3]); + *bias = signedUnsigned32.signed32; // Convert from unsigned to signed with no cast ambiguity + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::getBiasAccelY( int32_t* bias) +{ + if (_device._dmp_firmware_available == true) // Is DMP supported? + { + unsigned char bias_data[4] = { 0 }; + status = inv_icm20948_read_mems(&_device, ACCEL_BIAS_Y, 4, bias_data); + union { + int32_t signed32; + uint32_t unsigned32; + } signedUnsigned32; + signedUnsigned32.unsigned32 = (((uint32_t)bias_data[0]) << 24) | (((uint32_t)bias_data[1]) << 16) | (((uint32_t)bias_data[2]) << 8) | (bias_data[3]); + *bias = signedUnsigned32.signed32; // Convert from unsigned to signed with no cast ambiguity + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::getBiasAccelZ( int32_t* bias) +{ + if (_device._dmp_firmware_available == true) // Is DMP supported? + { + unsigned char bias_data[4] = { 0 }; + status = inv_icm20948_read_mems(&_device, ACCEL_BIAS_Z, 4, bias_data); + union { + int32_t signed32; + uint32_t unsigned32; + } signedUnsigned32; + signedUnsigned32.unsigned32 = (((uint32_t)bias_data[0]) << 24) | (((uint32_t)bias_data[1]) << 16) | (((uint32_t)bias_data[2]) << 8) | (bias_data[3]); + *bias = signedUnsigned32.signed32; // Convert from unsigned to signed with no cast ambiguity + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} +//CPass Bias +ICM_20948_Status_e ICM_20948::setBiasCPassX( int32_t newValue) +{ + if (_device._dmp_firmware_available == true) // Is DMP supported? + { + unsigned char cpass_bias_reg[4]; + cpass_bias_reg[0] = (unsigned char)(newValue >> 24); + cpass_bias_reg[1] = (unsigned char)(newValue >> 16); + cpass_bias_reg[2] = (unsigned char)(newValue >> 8); + cpass_bias_reg[3] = (unsigned char)(newValue & 0xff); + status = inv_icm20948_write_mems(&_device, CPASS_BIAS_X, 4, (const unsigned char*)&cpass_bias_reg); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::setBiasCPassY( int32_t newValue) +{ + if (_device._dmp_firmware_available == true) // Is DMP supported? + { + unsigned char cpass_bias_reg[4]; + cpass_bias_reg[0] = (unsigned char)(newValue >> 24); + cpass_bias_reg[1] = (unsigned char)(newValue >> 16); + cpass_bias_reg[2] = (unsigned char)(newValue >> 8); + cpass_bias_reg[3] = (unsigned char)(newValue & 0xff); + status = inv_icm20948_write_mems(&_device, CPASS_BIAS_Y, 4, (const unsigned char*)&cpass_bias_reg); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::setBiasCPassZ( int32_t newValue) +{ + if (_device._dmp_firmware_available == true) // Is DMP supported? + { + unsigned char cpass_bias_reg[4]; + cpass_bias_reg[0] = (unsigned char)(newValue >> 24); + cpass_bias_reg[1] = (unsigned char)(newValue >> 16); + cpass_bias_reg[2] = (unsigned char)(newValue >> 8); + cpass_bias_reg[3] = (unsigned char)(newValue & 0xff); + status = inv_icm20948_write_mems(&_device, CPASS_BIAS_Z, 4, (const unsigned char*)&cpass_bias_reg); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::getBiasCPassX( int32_t* bias) +{ + if (_device._dmp_firmware_available == true) // Is DMP supported? + { + unsigned char bias_data[4] = { 0 }; + status = inv_icm20948_read_mems(&_device, CPASS_BIAS_X, 4, bias_data); + union { + int32_t signed32; + uint32_t unsigned32; + } signedUnsigned32; + signedUnsigned32.unsigned32 = (((uint32_t)bias_data[0]) << 24) | (((uint32_t)bias_data[1]) << 16) | (((uint32_t)bias_data[2]) << 8) | (bias_data[3]); + *bias = signedUnsigned32.signed32; // Convert from unsigned to signed with no cast ambiguity + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::getBiasCPassY( int32_t* bias) +{ + if (_device._dmp_firmware_available == true) // Is DMP supported? + { + unsigned char bias_data[4] = { 0 }; + status = inv_icm20948_read_mems(&_device, CPASS_BIAS_Y, 4, bias_data); + union { + int32_t signed32; + uint32_t unsigned32; + } signedUnsigned32; + signedUnsigned32.unsigned32 = (((uint32_t)bias_data[0]) << 24) | (((uint32_t)bias_data[1]) << 16) | (((uint32_t)bias_data[2]) << 8) | (bias_data[3]); + *bias = signedUnsigned32.signed32; // Convert from unsigned to signed with no cast ambiguity + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::getBiasCPassZ( int32_t* bias) +{ + if (_device._dmp_firmware_available == true) // Is DMP supported? + { + unsigned char bias_data[4] = { 0 }; + status = inv_icm20948_read_mems(&_device, CPASS_BIAS_Z, 4, bias_data); + union { + int32_t signed32; + uint32_t unsigned32; + } signedUnsigned32; + signedUnsigned32.unsigned32 = (((uint32_t)bias_data[0]) << 24) | (((uint32_t)bias_data[1]) << 16) | (((uint32_t)bias_data[2]) << 8) | (bias_data[3]); + *bias = signedUnsigned32.signed32; // Convert from unsigned to signed with no cast ambiguity + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +float ICM_20948::temp(void) +{ + return getTempC(agmt.tmp.val); +} + +float ICM_20948::getTempC(int16_t val) +{ + return (((float)val - 21) / 333.87) + 21; +} + +const char *ICM_20948::statusString(ICM_20948_Status_e stat) +{ + ICM_20948_Status_e val; + if (stat == ICM_20948_Stat_NUM) + { + val = status; + } + else + { + val = stat; + } + + switch (val) + { + case ICM_20948_Stat_Ok: + return "All is well."; + break; + case ICM_20948_Stat_Err: + return "General Error"; + break; + case ICM_20948_Stat_NotImpl: + return "Not Implemented"; + break; + case ICM_20948_Stat_ParamErr: + return "Parameter Error"; + break; + case ICM_20948_Stat_WrongID: + return "Wrong ID"; + break; + case ICM_20948_Stat_InvalSensor: + return "Invalid Sensor"; + break; + case ICM_20948_Stat_NoData: + return "Data Underflow"; + break; + case ICM_20948_Stat_SensorNotSupported: + return "Sensor Not Supported"; + break; + case ICM_20948_Stat_DMPNotSupported: + return "DMP Firmware Not Supported. Is #define ICM_20948_USE_DMP commented in util/ICM_20948_C.h?"; + break; + case ICM_20948_Stat_DMPVerifyFail: + return "DMP Firmware Verification Failed"; + break; + case ICM_20948_Stat_FIFONoDataAvail: + return "No FIFO Data Available"; + break; + case ICM_20948_Stat_FIFOIncompleteData: + return "DMP data in FIFO was incomplete"; + break; + case ICM_20948_Stat_FIFOMoreDataAvail: + return "More FIFO Data Available"; + break; + case ICM_20948_Stat_UnrecognisedDMPHeader: + return "Unrecognised DMP Header"; + break; + case ICM_20948_Stat_UnrecognisedDMPHeader2: + return "Unrecognised DMP Header2"; + break; + case ICM_20948_Stat_InvalDMPRegister: + return "Invalid DMP Register"; + break; + default: + return "Unknown Status"; + break; + } + return "None"; +} + +// Device Level +ICM_20948_Status_e ICM_20948::setBank(uint8_t bank) +{ + status = ICM_20948_set_bank(&_device, bank); + return status; +} + +ICM_20948_Status_e ICM_20948::swReset(void) +{ + status = ICM_20948_sw_reset(&_device); + return status; +} + +ICM_20948_Status_e ICM_20948::sleep(bool on) +{ + status = ICM_20948_sleep(&_device, on); + return status; +} + +ICM_20948_Status_e ICM_20948::lowPower(bool on) +{ + status = ICM_20948_low_power(&_device, on); + return status; +} + +ICM_20948_Status_e ICM_20948::setClockSource(ICM_20948_PWR_MGMT_1_CLKSEL_e source) +{ + status = ICM_20948_set_clock_source(&_device, source); + return status; +} + +ICM_20948_Status_e ICM_20948::checkID(void) +{ + status = ICM_20948_check_id(&_device); + if (status != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::checkID: ICM_20948_check_id returned: ")); + debugPrintStatus(status); + debugPrintln(F("")); + } + return status; +} + +bool ICM_20948::dataReady(void) +{ + status = ICM_20948_data_ready(&_device); + if (status == ICM_20948_Stat_Ok) + { + return true; + } + return false; +} + +uint8_t ICM_20948::getWhoAmI(void) +{ + uint8_t retval = 0x00; + status = ICM_20948_get_who_am_i(&_device, &retval); + return retval; +} + +bool ICM_20948::isConnected(void) +{ + status = checkID(); + if (status == ICM_20948_Stat_Ok) + { + return true; + } + debugPrint(F("ICM_20948::isConnected: checkID returned: ")); + debugPrintStatus(status); + debugPrintln(F("")); + return false; +} + +// Internal Sensor Options +ICM_20948_Status_e ICM_20948::setSampleMode(uint8_t sensor_id_bm, uint8_t lp_config_cycle_mode) +{ + status = ICM_20948_set_sample_mode(&_device, (ICM_20948_InternalSensorID_bm)sensor_id_bm, (ICM_20948_LP_CONFIG_CYCLE_e)lp_config_cycle_mode); + delay(1); // Give the ICM20948 time to change the sample mode (see issue #8) + return status; +} + +ICM_20948_Status_e ICM_20948::setFullScale(uint8_t sensor_id_bm, ICM_20948_fss_t fss) +{ + status = ICM_20948_set_full_scale(&_device, (ICM_20948_InternalSensorID_bm)sensor_id_bm, fss); + return status; +} + +ICM_20948_Status_e ICM_20948::setDLPFcfg(uint8_t sensor_id_bm, ICM_20948_dlpcfg_t cfg) +{ + status = ICM_20948_set_dlpf_cfg(&_device, (ICM_20948_InternalSensorID_bm)sensor_id_bm, cfg); + return status; +} + +ICM_20948_Status_e ICM_20948::enableDLPF(uint8_t sensor_id_bm, bool enable) +{ + status = ICM_20948_enable_dlpf(&_device, (ICM_20948_InternalSensorID_bm)sensor_id_bm, enable); + return status; +} + +ICM_20948_Status_e ICM_20948::setSampleRate(uint8_t sensor_id_bm, ICM_20948_smplrt_t smplrt) +{ + status = ICM_20948_set_sample_rate(&_device, (ICM_20948_InternalSensorID_bm)sensor_id_bm, smplrt); + return status; +} + +// Interrupts on INT Pin +ICM_20948_Status_e ICM_20948::clearInterrupts(void) +{ + ICM_20948_INT_STATUS_t int_stat; + ICM_20948_INT_STATUS_1_t int_stat_1; + + // read to clear interrupts + status = ICM_20948_set_bank(&_device, 0); + if (status != ICM_20948_Stat_Ok) + { + return status; + } + status = ICM_20948_execute_r(&_device, AGB0_REG_INT_STATUS, (uint8_t *)&int_stat, sizeof(ICM_20948_INT_STATUS_t)); + if (status != ICM_20948_Stat_Ok) + { + return status; + } + status = ICM_20948_execute_r(&_device, AGB0_REG_INT_STATUS_1, (uint8_t *)&int_stat_1, sizeof(ICM_20948_INT_STATUS_1_t)); + if (status != ICM_20948_Stat_Ok) + { + return status; + } + + // todo: there may be additional interrupts that need to be cleared, like FIFO overflow/watermark + + return status; +} + +ICM_20948_Status_e ICM_20948::cfgIntActiveLow(bool active_low) +{ + ICM_20948_INT_PIN_CFG_t reg; + status = ICM_20948_int_pin_cfg(&_device, NULL, ®); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + reg.INT1_ACTL = active_low; // set the setting + status = ICM_20948_int_pin_cfg(&_device, ®, NULL); // write phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::cfgIntOpenDrain(bool open_drain) +{ + ICM_20948_INT_PIN_CFG_t reg; + status = ICM_20948_int_pin_cfg(&_device, NULL, ®); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + reg.INT1_OPEN = open_drain; // set the setting + status = ICM_20948_int_pin_cfg(&_device, ®, NULL); // write phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::cfgIntLatch(bool latching) +{ + ICM_20948_INT_PIN_CFG_t reg; + status = ICM_20948_int_pin_cfg(&_device, NULL, ®); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + reg.INT1_LATCH_EN = latching; // set the setting + status = ICM_20948_int_pin_cfg(&_device, ®, NULL); // write phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::cfgIntAnyReadToClear(bool enabled) +{ + ICM_20948_INT_PIN_CFG_t reg; + status = ICM_20948_int_pin_cfg(&_device, NULL, ®); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + reg.INT_ANYRD_2CLEAR = enabled; // set the setting + status = ICM_20948_int_pin_cfg(&_device, ®, NULL); // write phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::cfgFsyncActiveLow(bool active_low) +{ + ICM_20948_INT_PIN_CFG_t reg; + status = ICM_20948_int_pin_cfg(&_device, NULL, ®); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + reg.ACTL_FSYNC = active_low; // set the setting + status = ICM_20948_int_pin_cfg(&_device, ®, NULL); // write phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::cfgFsyncIntMode(bool interrupt_mode) +{ + ICM_20948_INT_PIN_CFG_t reg; + status = ICM_20948_int_pin_cfg(&_device, NULL, ®); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + reg.FSYNC_INT_MODE_EN = interrupt_mode; // set the setting + status = ICM_20948_int_pin_cfg(&_device, ®, NULL); // write phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + return status; +} + +// All these individual functions will use a read->set->write method to leave other settings untouched +ICM_20948_Status_e ICM_20948::intEnableI2C(bool enable) +{ + ICM_20948_INT_enable_t en; // storage + status = ICM_20948_int_enable(&_device, NULL, &en); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + en.I2C_MST_INT_EN = enable; // change the setting + status = ICM_20948_int_enable(&_device, &en, &en); // write phase w/ readback + if (status != ICM_20948_Stat_Ok) + { + return status; + } + if (en.I2C_MST_INT_EN != enable) + { + status = ICM_20948_Stat_Err; + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::intEnableDMP(bool enable) +{ + ICM_20948_INT_enable_t en; // storage + status = ICM_20948_int_enable(&_device, NULL, &en); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + en.DMP_INT1_EN = enable; // change the setting + status = ICM_20948_int_enable(&_device, &en, &en); // write phase w/ readback + if (status != ICM_20948_Stat_Ok) + { + return status; + } + if (en.DMP_INT1_EN != enable) + { + status = ICM_20948_Stat_Err; + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::intEnablePLL(bool enable) +{ + ICM_20948_INT_enable_t en; // storage + status = ICM_20948_int_enable(&_device, NULL, &en); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + en.PLL_RDY_EN = enable; // change the setting + status = ICM_20948_int_enable(&_device, &en, &en); // write phase w/ readback + if (status != ICM_20948_Stat_Ok) + { + return status; + } + if (en.PLL_RDY_EN != enable) + { + status = ICM_20948_Stat_Err; + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::intEnableWOM(bool enable) +{ + ICM_20948_INT_enable_t en; // storage + status = ICM_20948_int_enable(&_device, NULL, &en); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + en.WOM_INT_EN = enable; // change the setting + status = ICM_20948_int_enable(&_device, &en, &en); // write phase w/ readback + if (status != ICM_20948_Stat_Ok) + { + return status; + } + if (en.WOM_INT_EN != enable) + { + status = ICM_20948_Stat_Err; + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::intEnableWOF(bool enable) +{ + ICM_20948_INT_enable_t en; // storage + status = ICM_20948_int_enable(&_device, NULL, &en); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + en.REG_WOF_EN = enable; // change the setting + status = ICM_20948_int_enable(&_device, &en, &en); // write phase w/ readback + if (status != ICM_20948_Stat_Ok) + { + return status; + } + if (en.REG_WOF_EN != enable) + { + status = ICM_20948_Stat_Err; + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::intEnableRawDataReady(bool enable) +{ + ICM_20948_INT_enable_t en; // storage + status = ICM_20948_int_enable(&_device, NULL, &en); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + en.RAW_DATA_0_RDY_EN = enable; // change the setting + status = ICM_20948_int_enable(&_device, &en, &en); // write phase w/ readback + if (status != ICM_20948_Stat_Ok) + { + return status; + } + if (en.RAW_DATA_0_RDY_EN != enable) + { + status = ICM_20948_Stat_Err; + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::intEnableOverflowFIFO(uint8_t bm_enable) +{ + ICM_20948_INT_enable_t en; // storage + status = ICM_20948_int_enable(&_device, NULL, &en); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + en.FIFO_OVERFLOW_EN_0 = ((bm_enable >> 0) & 0x01); // change the settings + en.FIFO_OVERFLOW_EN_1 = ((bm_enable >> 1) & 0x01); + en.FIFO_OVERFLOW_EN_2 = ((bm_enable >> 2) & 0x01); + en.FIFO_OVERFLOW_EN_3 = ((bm_enable >> 3) & 0x01); + en.FIFO_OVERFLOW_EN_4 = ((bm_enable >> 4) & 0x01); + status = ICM_20948_int_enable(&_device, &en, &en); // write phase w/ readback + if (status != ICM_20948_Stat_Ok) + { + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::intEnableWatermarkFIFO(uint8_t bm_enable) +{ + ICM_20948_INT_enable_t en; // storage + status = ICM_20948_int_enable(&_device, NULL, &en); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + en.FIFO_WM_EN_0 = ((bm_enable >> 0) & 0x01); // change the settings + en.FIFO_WM_EN_1 = ((bm_enable >> 1) & 0x01); + en.FIFO_WM_EN_2 = ((bm_enable >> 2) & 0x01); + en.FIFO_WM_EN_3 = ((bm_enable >> 3) & 0x01); + en.FIFO_WM_EN_4 = ((bm_enable >> 4) & 0x01); + status = ICM_20948_int_enable(&_device, &en, &en); // write phase w/ readback + if (status != ICM_20948_Stat_Ok) + { + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::WOMThreshold(uint8_t threshold) +{ + ICM_20948_ACCEL_WOM_THR_t thr; // storage + status = ICM_20948_wom_threshold(&_device, NULL, &thr); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + thr.WOM_THRESHOLD = threshold; // change the setting + status = ICM_20948_wom_threshold(&_device, &thr, &thr); // write phase w/ readback + if (status != ICM_20948_Stat_Ok) + { + return status; + } + if (thr.WOM_THRESHOLD != threshold) + { + status = ICM_20948_Stat_Err; + return status; + } + return status; +} + +// Interface Options +ICM_20948_Status_e ICM_20948::i2cMasterPassthrough(bool passthrough) +{ + status = ICM_20948_i2c_master_passthrough(&_device, passthrough); + return status; +} + +ICM_20948_Status_e ICM_20948::i2cMasterEnable(bool enable) +{ + status = ICM_20948_i2c_master_enable(&_device, enable); + return status; +} + +ICM_20948_Status_e ICM_20948::i2cMasterReset() +{ + status = ICM_20948_i2c_master_reset(&_device); + return status; +} + +ICM_20948_Status_e ICM_20948::i2cControllerConfigurePeripheral(uint8_t peripheral, uint8_t addr, uint8_t reg, uint8_t len, bool Rw, bool enable, bool data_only, bool grp, bool swap, uint8_t dataOut) +{ + status = ICM_20948_i2c_controller_configure_peripheral(&_device, peripheral, addr, reg, len, Rw, enable, data_only, grp, swap, dataOut); + return status; +} + +//Provided for backward-compatibility only. Please update to i2cControllerConfigurePeripheral and i2cControllerPeriph4Transaction. +//https://www.oshwa.org/2020/06/29/a-resolution-to-redefine-spi-pin-names/ +ICM_20948_Status_e ICM_20948::i2cMasterConfigureSlave(uint8_t peripheral, uint8_t addr, uint8_t reg, uint8_t len, bool Rw, bool enable, bool data_only, bool grp, bool swap) +{ + return (i2cControllerConfigurePeripheral(peripheral, addr, reg, len, Rw, enable, data_only, grp, swap, 0)); +} + +ICM_20948_Status_e ICM_20948::i2cControllerPeriph4Transaction(uint8_t addr, uint8_t reg, uint8_t *data, uint8_t len, bool Rw, bool send_reg_addr) +{ + status = ICM_20948_i2c_controller_periph4_txn(&_device, addr, reg, data, len, Rw, send_reg_addr); + return status; +} + +//Provided for backward-compatibility only. Please update to i2cControllerConfigurePeripheral and i2cControllerPeriph4Transaction. +//https://www.oshwa.org/2020/06/29/a-resolution-to-redefine-spi-pin-names/ +ICM_20948_Status_e ICM_20948::i2cMasterSLV4Transaction(uint8_t addr, uint8_t reg, uint8_t *data, uint8_t len, bool Rw, bool send_reg_addr) +{ + return (i2cControllerPeriph4Transaction(addr, reg, data, len, Rw, send_reg_addr)); +} + +ICM_20948_Status_e ICM_20948::i2cMasterSingleW(uint8_t addr, uint8_t reg, uint8_t data) +{ + status = ICM_20948_i2c_master_single_w(&_device, addr, reg, &data); + return status; +} +uint8_t ICM_20948::i2cMasterSingleR(uint8_t addr, uint8_t reg) +{ + uint8_t data = 0; + status = ICM_20948_i2c_master_single_r(&_device, addr, reg, &data); + if (status != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::i2cMasterSingleR: ICM_20948_i2c_master_single_r returned: ")); + debugPrintStatus(status); + debugPrintln(F("")); + } + return data; +} + +ICM_20948_Status_e ICM_20948::startupDefault(bool minimal) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + retval = checkID(); + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupDefault: checkID returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + + retval = swReset(); + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupDefault: swReset returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + delay(50); + + retval = sleep(false); + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupDefault: sleep returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + + retval = lowPower(false); + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupDefault: lowPower returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + + retval = startupMagnetometer(minimal); // Pass the minimal startup flag to startupMagnetometer + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupDefault: startupMagnetometer returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + + if (minimal) // Return now if minimal is true + { + debugPrintln(F("ICM_20948::startupDefault: minimal startup complete!")); + return status; + } + + retval = setSampleMode((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), ICM_20948_Sample_Mode_Continuous); // options: ICM_20948_Sample_Mode_Continuous or ICM_20948_Sample_Mode_Cycled + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupDefault: setSampleMode returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } // sensors: ICM_20948_Internal_Acc, ICM_20948_Internal_Gyr, ICM_20948_Internal_Mst + + ICM_20948_fss_t FSS; + FSS.a = gpm2; // (ICM_20948_ACCEL_CONFIG_FS_SEL_e) + FSS.g = dps250; // (ICM_20948_GYRO_CONFIG_1_FS_SEL_e) + retval = setFullScale((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), FSS); + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupDefault: setFullScale returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + + ICM_20948_dlpcfg_t dlpcfg; + dlpcfg.a = acc_d473bw_n499bw; + dlpcfg.g = gyr_d361bw4_n376bw5; + retval = setDLPFcfg((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), dlpcfg); + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupDefault: setDLPFcfg returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + + retval = enableDLPF(ICM_20948_Internal_Acc, false); + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupDefault: enableDLPF (Acc) returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + + retval = enableDLPF(ICM_20948_Internal_Gyr, false); + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupDefault: enableDLPF (Gyr) returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + + return status; +} + +// direct read/write +ICM_20948_Status_e ICM_20948::read(uint8_t reg, uint8_t *pdata, uint32_t len) +{ + status = ICM_20948_execute_r(&_device, reg, pdata, len); + return (status); +} + +ICM_20948_Status_e ICM_20948::write(uint8_t reg, uint8_t *pdata, uint32_t len) +{ + status = ICM_20948_execute_w(&_device, reg, pdata, len); + return (status); +} + +uint8_t ICM_20948::readMag(AK09916_Reg_Addr_e reg) +{ + uint8_t data = i2cMasterSingleR(MAG_AK09916_I2C_ADDR, reg); // i2cMasterSingleR updates status too + return data; +} + +ICM_20948_Status_e ICM_20948::writeMag(AK09916_Reg_Addr_e reg, uint8_t *pdata) +{ + status = i2cMasterSingleW(MAG_AK09916_I2C_ADDR, reg, *pdata); + return status; +} + +ICM_20948_Status_e ICM_20948::resetMag() +{ + uint8_t SRST = 1; + // SRST: Soft reset + // “0”: Normal + // “1”: Reset + // When “1” is set, all registers are initialized. After reset, SRST bit turns to “0” automatically. + status = i2cMasterSingleW(MAG_AK09916_I2C_ADDR, AK09916_REG_CNTL3, SRST); + return status; +} + +// FIFO + +ICM_20948_Status_e ICM_20948::enableFIFO(bool enable) +{ + status = ICM_20948_enable_FIFO(&_device, enable); + return status; +} + +ICM_20948_Status_e ICM_20948::resetFIFO(void) +{ + status = ICM_20948_reset_FIFO(&_device); + return status; +} + +ICM_20948_Status_e ICM_20948::setFIFOmode(bool snapshot) +{ + // Default to Stream (non-Snapshot) mode + status = ICM_20948_set_FIFO_mode(&_device, snapshot); + return status; +} + +ICM_20948_Status_e ICM_20948::getFIFOcount(uint16_t *count) +{ + status = ICM_20948_get_FIFO_count(&_device, count); + return status; +} + +ICM_20948_Status_e ICM_20948::readFIFO(uint8_t *data, uint8_t len) +{ + status = ICM_20948_read_FIFO(&_device, data, len); + return status; +} + +// DMP + +ICM_20948_Status_e ICM_20948::enableDMP(bool enable) +{ + if (_device._dmp_firmware_available == true) // Should we attempt to enable the DMP? + { + status = ICM_20948_enable_DMP(&_device, enable == true ? 1 : 0); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::resetDMP(void) +{ + status = ICM_20948_reset_DMP(&_device); + return status; +} + +ICM_20948_Status_e ICM_20948::loadDMPFirmware(void) +{ + if (_device._dmp_firmware_available == true) // Should we attempt to load the DMP firmware? + { + status = ICM_20948_firmware_load(&_device); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::setDMPstartAddress(unsigned short address) +{ + if (_device._dmp_firmware_available == true) // Should we attempt to set the start address? + { + status = ICM_20948_set_dmp_start_address(&_device, address); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::enableDMPSensor(enum inv_icm20948_sensor sensor, bool enable) +{ + if (_device._dmp_firmware_available == true) // Should we attempt to enable the sensor? + { + status = inv_icm20948_enable_dmp_sensor(&_device, sensor, enable == true ? 1 : 0); + debugPrint(F("ICM_20948::enableDMPSensor: _enabled_Android_0: ")); + debugPrintf((int)_device._enabled_Android_0); + debugPrint(F(" _enabled_Android_1: ")); + debugPrintf((int)_device._enabled_Android_1); + debugPrint(F(" _dataOutCtl1: ")); + debugPrintf((int)_device._dataOutCtl1); + debugPrint(F(" _dataOutCtl2: ")); + debugPrintf((int)_device._dataOutCtl2); + debugPrint(F(" _dataRdyStatus: ")); + debugPrintf((int)_device._dataRdyStatus); + debugPrintln(F("")); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::enableDMPSensorInt(enum inv_icm20948_sensor sensor, bool enable) +{ + if (_device._dmp_firmware_available == true) // Should we attempt to enable the sensor interrupt? + { + status = inv_icm20948_enable_dmp_sensor_int(&_device, sensor, enable == true ? 1 : 0); + debugPrint(F("ICM_20948::enableDMPSensorInt: _enabled_Android_intr_0: ")); + debugPrintf((int)_device._enabled_Android_intr_0); + debugPrint(F(" _enabled_Android_intr_1: ")); + debugPrintf((int)_device._enabled_Android_intr_1); + debugPrint(F(" _dataIntrCtl: ")); + debugPrintf((int)_device._dataIntrCtl); + debugPrintln(F("")); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::writeDMPmems(unsigned short reg, unsigned int length, const unsigned char *data) +{ + if (_device._dmp_firmware_available == true) // Should we attempt to write to the DMP? + { + status = inv_icm20948_write_mems(&_device, reg, length, data); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::readDMPmems(unsigned short reg, unsigned int length, unsigned char *data) +{ + if (_device._dmp_firmware_available == true) // Should we attempt to read from the DMP? + { + status = inv_icm20948_read_mems(&_device, reg, length, data); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::setDMPODRrate(enum DMP_ODR_Registers odr_reg, int interval) +{ + if (_device._dmp_firmware_available == true) // Should we attempt to set the DMP ODR? + { + // In order to set an ODR for a given sensor data, write 2-byte value to DMP using key defined above for a particular sensor. + // Setting value can be calculated as follows: + // Value = (DMP running rate (225Hz) / ODR ) - 1 + // E.g. For a 25Hz ODR rate, value= (225/25) - 1 = 8. + + status = inv_icm20948_set_dmp_sensor_period(&_device, odr_reg, interval); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::readDMPdataFromFIFO(icm_20948_DMP_data_t *data) +{ + if (_device._dmp_firmware_available == true) // Should we attempt to set the data from the FIFO? + { + status = inv_icm20948_read_dmp_data(&_device, data); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::setGyroSF(unsigned char div, int gyro_level) +{ + if (_device._dmp_firmware_available == true) // Should we attempt to set the Gyro SF? + { + status = inv_icm20948_set_gyro_sf(&_device, div, gyro_level); + debugPrint(F("ICM_20948::setGyroSF: pll: ")); + debugPrintf((int)_device._gyroSFpll); + debugPrint(F(" Gyro SF is: ")); + debugPrintf((int)_device._gyroSF); + debugPrintln(F("")); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +// Combine all of the DMP start-up code from the earlier DMP examples +// This function is defined as __attribute__((weak)) so you can overwrite it if you want to, +// e.g. to modify the sample rate +ICM_20948_Status_e ICM_20948::initializeDMP(void) +{ + // First, let's check if the DMP is available + if (_device._dmp_firmware_available != true) + { + debugPrint(F("ICM_20948::startupDMP: DMP is not available. Please check that you have uncommented line 29 (#define ICM_20948_USE_DMP) in ICM_20948_C.h...")); + return ICM_20948_Stat_DMPNotSupported; + } + + ICM_20948_Status_e worstResult = ICM_20948_Stat_Ok; + +#if defined(ICM_20948_USE_DMP) + + // The ICM-20948 is awake and ready but hasn't been configured. Let's step through the configuration + // sequence from InvenSense's _confidential_ Application Note "Programming Sequence for DMP Hardware Functions". + + ICM_20948_Status_e result = ICM_20948_Stat_Ok; // Use result and worstResult to show if the configuration was successful + + // Normally, when the DMP is not enabled, startupMagnetometer (called by startupDefault, which is called by begin) configures the AK09916 magnetometer + // to run at 100Hz by setting the CNTL2 register (0x31) to 0x08. Then the ICM20948's I2C_SLV0 is configured to read + // nine bytes from the mag every sample, starting from the STATUS1 register (0x10). ST1 includes the DRDY (Data Ready) bit. + // Next are the six magnetometer readings (little endian). After a dummy byte, the STATUS2 register (0x18) contains the HOFL (Overflow) bit. + // + // But looking very closely at the InvenSense example code, we can see in inv_icm20948_resume_akm (in Icm20948AuxCompassAkm.c) that, + // when the DMP is running, the magnetometer is set to Single Measurement (SM) mode and that ten bytes are read, starting from the reserved + // RSV2 register (0x03). The datasheet does not define what registers 0x04 to 0x0C contain. There is definitely some secret sauce in here... + // The magnetometer data appears to be big endian (not little endian like the HX/Y/Z registers) and starts at register 0x04. + // We had to examine the I2C traffic between the master and the AK09916 on the AUX_DA and AUX_CL pins to discover this... + // + // So, we need to set up I2C_SLV0 to do the ten byte reading. The parameters passed to i2cControllerConfigurePeripheral are: + // 0: use I2C_SLV0 + // MAG_AK09916_I2C_ADDR: the I2C address of the AK09916 magnetometer (0x0C unshifted) + // AK09916_REG_RSV2: we start reading here (0x03). Secret sauce... + // 10: we read 10 bytes each cycle + // true: set the I2C_SLV0_RNW ReadNotWrite bit so we read the 10 bytes (not write them) + // true: set the I2C_SLV0_CTRL I2C_SLV0_EN bit to enable reading from the peripheral at the sample rate + // false: clear the I2C_SLV0_CTRL I2C_SLV0_REG_DIS (we want to write the register value) + // true: set the I2C_SLV0_CTRL I2C_SLV0_GRP bit to show the register pairing starts at byte 1+2 (copied from inv_icm20948_resume_akm) + // true: set the I2C_SLV0_CTRL I2C_SLV0_BYTE_SW to byte-swap the data from the mag (copied from inv_icm20948_resume_akm) + result = i2cControllerConfigurePeripheral(0, MAG_AK09916_I2C_ADDR, AK09916_REG_RSV2, 10, true, true, false, true, true); if (result > worstResult) worstResult = result; + // + // We also need to set up I2C_SLV1 to do the Single Measurement triggering: + // 1: use I2C_SLV1 + // MAG_AK09916_I2C_ADDR: the I2C address of the AK09916 magnetometer (0x0C unshifted) + // AK09916_REG_CNTL2: we start writing here (0x31) + // 1: not sure why, but the write does not happen if this is set to zero + // false: clear the I2C_SLV0_RNW ReadNotWrite bit so we write the dataOut byte + // true: set the I2C_SLV0_CTRL I2C_SLV0_EN bit. Not sure why, but the write does not happen if this is clear + // false: clear the I2C_SLV0_CTRL I2C_SLV0_REG_DIS (we want to write the register value) + // false: clear the I2C_SLV0_CTRL I2C_SLV0_GRP bit + // false: clear the I2C_SLV0_CTRL I2C_SLV0_BYTE_SW bit + // AK09916_mode_single: tell I2C_SLV1 to write the Single Measurement command each sample + result = i2cControllerConfigurePeripheral(1, MAG_AK09916_I2C_ADDR, AK09916_REG_CNTL2, 1, false, true, false, false, false, AK09916_mode_single); if (result > worstResult) worstResult = result; + + // Set the I2C Master ODR configuration + // It is not clear why we need to do this... But it appears to be essential! From the datasheet: + // "I2C_MST_ODR_CONFIG[3:0]: ODR configuration for external sensor when gyroscope and accelerometer are disabled. + // ODR is computed as follows: 1.1 kHz/(2^((odr_config[3:0])) ) + // When gyroscope is enabled, all sensors (including I2C_MASTER) use the gyroscope ODR. + // If gyroscope is disabled, then all sensors (including I2C_MASTER) use the accelerometer ODR." + // Since both gyro and accel are running, setting this register should have no effect. But it does. Maybe because the Gyro and Accel are placed in Low Power Mode (cycled)? + // You can see by monitoring the Aux I2C pins that the next three lines reduce the bus traffic (magnetometer reads) from 1125Hz to the chosen rate: 68.75Hz in this case. + result = setBank(3); if (result > worstResult) worstResult = result; // Select Bank 3 + uint8_t mstODRconfig = 0x04; // Set the ODR configuration to 1100/2^4 = 68.75Hz + result = write(AGB3_REG_I2C_MST_ODR_CONFIG, &mstODRconfig, 1); if (result > worstResult) worstResult = result; // Write one byte to the I2C_MST_ODR_CONFIG register + + // Configure clock source through PWR_MGMT_1 + // ICM_20948_Clock_Auto selects the best available clock source – PLL if ready, else use the Internal oscillator + result = setClockSource(ICM_20948_Clock_Auto); if (result > worstResult) worstResult = result; // This is shorthand: success will be set to false if setClockSource fails + + // Enable accel and gyro sensors through PWR_MGMT_2 + // Enable Accelerometer (all axes) and Gyroscope (all axes) by writing zero to PWR_MGMT_2 + result = setBank(0); if (result > worstResult) worstResult = result; // Select Bank 0 + uint8_t pwrMgmt2 = 0x40; // Set the reserved bit 6 (pressure sensor disable?) + result = write(AGB0_REG_PWR_MGMT_2, &pwrMgmt2, 1); if (result > worstResult) worstResult = result; // Write one byte to the PWR_MGMT_2 register + + // Place _only_ I2C_Master in Low Power Mode (cycled) via LP_CONFIG + // The InvenSense Nucleo example initially puts the accel and gyro into low power mode too, but then later updates LP_CONFIG so only the I2C_Master is in Low Power Mode + result = setSampleMode(ICM_20948_Internal_Mst, ICM_20948_Sample_Mode_Cycled); if (result > worstResult) worstResult = result; + + // Disable the FIFO + result = enableFIFO(false); if (result > worstResult) worstResult = result; + + // Disable the DMP + result = enableDMP(false); if (result > worstResult) worstResult = result; + + // Set Gyro FSR (Full scale range) to 2000dps through GYRO_CONFIG_1 + // Set Accel FSR (Full scale range) to 4g through ACCEL_CONFIG + ICM_20948_fss_t myFSS; // This uses a "Full Scale Settings" structure that can contain values for all configurable sensors + myFSS.a = gpm4; // (ICM_20948_ACCEL_CONFIG_FS_SEL_e) + // gpm2 + // gpm4 + // gpm8 + // gpm16 + myFSS.g = dps2000; // (ICM_20948_GYRO_CONFIG_1_FS_SEL_e) + // dps250 + // dps500 + // dps1000 + // dps2000 + result = setFullScale((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), myFSS); if (result > worstResult) worstResult = result; + + // The InvenSense Nucleo code also enables the gyro DLPF (but leaves GYRO_DLPFCFG set to zero = 196.6Hz (3dB)) + // We found this by going through the SPI data generated by ZaneL's Teensy-ICM-20948 library byte by byte... + // The gyro DLPF is enabled by default (GYRO_CONFIG_1 = 0x01) so the following line should have no effect, but we'll include it anyway + result = enableDLPF(ICM_20948_Internal_Gyr, true); if (result > worstResult) worstResult = result; + + // Enable interrupt for FIFO overflow from FIFOs through INT_ENABLE_2 + // If we see this interrupt, we'll need to reset the FIFO + //result = intEnableOverflowFIFO( 0x1F ); if (result > worstResult) worstResult = result; // Enable the interrupt on all FIFOs + + // Turn off what goes into the FIFO through FIFO_EN_1, FIFO_EN_2 + // Stop the peripheral data from being written to the FIFO by writing zero to FIFO_EN_1 + result = setBank(0); if (result > worstResult) worstResult = result; // Select Bank 0 + uint8_t zero = 0; + result = write(AGB0_REG_FIFO_EN_1, &zero, 1); if (result > worstResult) worstResult = result; + // Stop the accelerometer, gyro and temperature data from being written to the FIFO by writing zero to FIFO_EN_2 + result = write(AGB0_REG_FIFO_EN_2, &zero, 1); if (result > worstResult) worstResult = result; + + // Turn off data ready interrupt through INT_ENABLE_1 + result = intEnableRawDataReady(false); if (result > worstResult) worstResult = result; + + // Reset FIFO through FIFO_RST + result = resetFIFO(); if (result > worstResult) worstResult = result; + + // Set gyro sample rate divider with GYRO_SMPLRT_DIV + // Set accel sample rate divider with ACCEL_SMPLRT_DIV_2 + ICM_20948_smplrt_t mySmplrt; + mySmplrt.g = 19; // ODR is computed as follows: 1.1 kHz/(1+GYRO_SMPLRT_DIV[7:0]). 19 = 55Hz. InvenSense Nucleo example uses 19 (0x13). + mySmplrt.a = 19; // ODR is computed as follows: 1.125 kHz/(1+ACCEL_SMPLRT_DIV[11:0]). 19 = 56.25Hz. InvenSense Nucleo example uses 19 (0x13). + //mySmplrt.g = 4; // 225Hz + //mySmplrt.a = 4; // 225Hz + //mySmplrt.g = 8; // 112Hz + //mySmplrt.a = 8; // 112Hz + result = setSampleRate((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), mySmplrt); if (result > worstResult) worstResult = result; + + // Setup DMP start address through PRGM_STRT_ADDRH/PRGM_STRT_ADDRL + result = setDMPstartAddress(); if (result > worstResult) worstResult = result; // Defaults to DMP_START_ADDRESS + + // Now load the DMP firmware + result = loadDMPFirmware(); if (result > worstResult) worstResult = result; + + // Write the 2 byte Firmware Start Value to ICM PRGM_STRT_ADDRH/PRGM_STRT_ADDRL + result = setDMPstartAddress(); if (result > worstResult) worstResult = result; // Defaults to DMP_START_ADDRESS + + // Set the Hardware Fix Disable register to 0x48 + result = setBank(0); if (result > worstResult) worstResult = result; // Select Bank 0 + uint8_t fix = 0x48; + result = write(AGB0_REG_HW_FIX_DISABLE, &fix, 1); if (result > worstResult) worstResult = result; + + // Set the Single FIFO Priority Select register to 0xE4 + result = setBank(0); if (result > worstResult) worstResult = result; // Select Bank 0 + uint8_t fifoPrio = 0xE4; + result = write(AGB0_REG_SINGLE_FIFO_PRIORITY_SEL, &fifoPrio, 1); if (result > worstResult) worstResult = result; + + // Configure Accel scaling to DMP + // The DMP scales accel raw data internally to align 1g as 2^25 + // In order to align internal accel raw data 2^25 = 1g write 0x04000000 when FSR is 4g + const unsigned char accScale[4] = {0x04, 0x00, 0x00, 0x00}; + result = writeDMPmems(ACC_SCALE, 4, &accScale[0]); if (result > worstResult) worstResult = result; // Write accScale to ACC_SCALE DMP register + // In order to output hardware unit data as configured FSR write 0x00040000 when FSR is 4g + const unsigned char accScale2[4] = {0x00, 0x04, 0x00, 0x00}; + result = writeDMPmems(ACC_SCALE2, 4, &accScale2[0]); if (result > worstResult) worstResult = result; // Write accScale2 to ACC_SCALE2 DMP register + + // Configure Compass mount matrix and scale to DMP + // The mount matrix write to DMP register is used to align the compass axes with accel/gyro. + // This mechanism is also used to convert hardware unit to uT. The value is expressed as 1uT = 2^30. + // Each compass axis will be converted as below: + // X = raw_x * CPASS_MTX_00 + raw_y * CPASS_MTX_01 + raw_z * CPASS_MTX_02 + // Y = raw_x * CPASS_MTX_10 + raw_y * CPASS_MTX_11 + raw_z * CPASS_MTX_12 + // Z = raw_x * CPASS_MTX_20 + raw_y * CPASS_MTX_21 + raw_z * CPASS_MTX_22 + // The AK09916 produces a 16-bit signed output in the range +/-32752 corresponding to +/-4912uT. 1uT = 6.66 ADU. + // 2^30 / 6.66666 = 161061273 = 0x9999999 + const unsigned char mountMultiplierZero[4] = {0x00, 0x00, 0x00, 0x00}; + const unsigned char mountMultiplierPlus[4] = {0x09, 0x99, 0x99, 0x99}; // Value taken from InvenSense Nucleo example + const unsigned char mountMultiplierMinus[4] = {0xF6, 0x66, 0x66, 0x67}; // Value taken from InvenSense Nucleo example + result = writeDMPmems(CPASS_MTX_00, 4, &mountMultiplierPlus[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_01, 4, &mountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_02, 4, &mountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_10, 4, &mountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_11, 4, &mountMultiplierMinus[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_12, 4, &mountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_20, 4, &mountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_21, 4, &mountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_22, 4, &mountMultiplierMinus[0]); if (result > worstResult) worstResult = result; + + // Configure the B2S Mounting Matrix + const unsigned char b2sMountMultiplierZero[4] = {0x00, 0x00, 0x00, 0x00}; + const unsigned char b2sMountMultiplierPlus[4] = {0x40, 0x00, 0x00, 0x00}; // Value taken from InvenSense Nucleo example + result = writeDMPmems(B2S_MTX_00, 4, &b2sMountMultiplierPlus[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_01, 4, &b2sMountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_02, 4, &b2sMountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_10, 4, &b2sMountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_11, 4, &b2sMountMultiplierPlus[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_12, 4, &b2sMountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_20, 4, &b2sMountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_21, 4, &b2sMountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_22, 4, &b2sMountMultiplierPlus[0]); if (result > worstResult) worstResult = result; + + // Configure the DMP Gyro Scaling Factor + // @param[in] gyro_div Value written to GYRO_SMPLRT_DIV register, where + // 0=1125Hz sample rate, 1=562.5Hz sample rate, ... 4=225Hz sample rate, ... + // 10=102.2727Hz sample rate, ... etc. + // @param[in] gyro_level 0=250 dps, 1=500 dps, 2=1000 dps, 3=2000 dps + result = setGyroSF(19, 3); if (result > worstResult) worstResult = result; // 19 = 55Hz (see above), 3 = 2000dps (see above) + + // Configure the Gyro full scale + // 2000dps : 2^28 + // 1000dps : 2^27 + // 500dps : 2^26 + // 250dps : 2^25 + const unsigned char gyroFullScale[4] = {0x10, 0x00, 0x00, 0x00}; // 2000dps : 2^28 + result = writeDMPmems(GYRO_FULLSCALE, 4, &gyroFullScale[0]); if (result > worstResult) worstResult = result; + + // Configure the Accel Only Gain: 15252014 (225Hz) 30504029 (112Hz) 61117001 (56Hz) + const unsigned char accelOnlyGain[4] = {0x03, 0xA4, 0x92, 0x49}; // 56Hz + //const unsigned char accelOnlyGain[4] = {0x00, 0xE8, 0xBA, 0x2E}; // 225Hz + //const unsigned char accelOnlyGain[4] = {0x01, 0xD1, 0x74, 0x5D}; // 112Hz + result = writeDMPmems(ACCEL_ONLY_GAIN, 4, &accelOnlyGain[0]); if (result > worstResult) worstResult = result; + + // Configure the Accel Alpha Var: 1026019965 (225Hz) 977872018 (112Hz) 882002213 (56Hz) + const unsigned char accelAlphaVar[4] = {0x34, 0x92, 0x49, 0x25}; // 56Hz + //const unsigned char accelAlphaVar[4] = {0x3D, 0x27, 0xD2, 0x7D}; // 225Hz + //const unsigned char accelAlphaVar[4] = {0x3A, 0x49, 0x24, 0x92}; // 112Hz + result = writeDMPmems(ACCEL_ALPHA_VAR, 4, &accelAlphaVar[0]); if (result > worstResult) worstResult = result; + + // Configure the Accel A Var: 47721859 (225Hz) 95869806 (112Hz) 191739611 (56Hz) + const unsigned char accelAVar[4] = {0x0B, 0x6D, 0xB6, 0xDB}; // 56Hz + //const unsigned char accelAVar[4] = {0x02, 0xD8, 0x2D, 0x83}; // 225Hz + //const unsigned char accelAVar[4] = {0x05, 0xB6, 0xDB, 0x6E}; // 112Hz + result = writeDMPmems(ACCEL_A_VAR, 4, &accelAVar[0]); if (result > worstResult) worstResult = result; + + // Configure the Accel Cal Rate + const unsigned char accelCalRate[4] = {0x00, 0x00}; // Value taken from InvenSense Nucleo example + result = writeDMPmems(ACCEL_CAL_RATE, 2, &accelCalRate[0]); if (result > worstResult) worstResult = result; + + // Configure the Compass Time Buffer. The I2C Master ODR Configuration (see above) sets the magnetometer read rate to 68.75Hz. + // Let's set the Compass Time Buffer to 69 (Hz). + const unsigned char compassRate[2] = {0x00, 0x45}; // 69Hz + result = writeDMPmems(CPASS_TIME_BUFFER, 2, &compassRate[0]); if (result > worstResult) worstResult = result; + + // Enable DMP interrupt + // This would be the most efficient way of getting the DMP data, instead of polling the FIFO + //result = intEnableDMP(true); if (result > worstResult) worstResult = result; + +#endif + + return worstResult; +} + +// I2C +ICM_20948_I2C::ICM_20948_I2C() +{ +} + +ICM_20948_Status_e ICM_20948_I2C::begin(TwoWire &wirePort, bool ad0val, uint8_t ad0pin) +{ + // Associate + _ad0 = ad0pin; + _i2c = &wirePort; + _ad0val = ad0val; + + _addr = ICM_20948_I2C_ADDR_AD0; + if (_ad0val) + { + _addr = ICM_20948_I2C_ADDR_AD1; + } + + // Set pinmodes + if (_ad0 != ICM_20948_ARD_UNUSED_PIN) + { + pinMode(_ad0, OUTPUT); + } + + // Set pins to default positions + if (_ad0 != ICM_20948_ARD_UNUSED_PIN) + { + digitalWrite(_ad0, _ad0val); + } + + // _i2c->begin(); // Moved into user's sketch + + // Set up the serif + _serif.write = ICM_20948_write_I2C; + _serif.read = ICM_20948_read_I2C; + _serif.user = (void *)this; // refer to yourself in the user field + + // Link the serif + _device._serif = &_serif; + +#if defined(ICM_20948_USE_DMP) + _device._dmp_firmware_available = true; // Initialize _dmp_firmware_available +#else + _device._dmp_firmware_available = false; // Initialize _dmp_firmware_available +#endif + + _device._firmware_loaded = false; // Initialize _firmware_loaded + _device._last_bank = 255; // Initialize _last_bank. Make it invalid. It will be set by the first call of ICM_20948_set_bank. + _device._last_mems_bank = 255; // Initialize _last_mems_bank. Make it invalid. It will be set by the first call of inv_icm20948_write_mems. + _device._gyroSF = 0; // Use this to record the GyroSF, calculated by inv_icm20948_set_gyro_sf + _device._gyroSFpll = 0; + _device._enabled_Android_0 = 0; // Keep track of which Android sensors are enabled: 0-31 + _device._enabled_Android_1 = 0; // Keep track of which Android sensors are enabled: 32- + _device._enabled_Android_intr_0 = 0; // Keep track of which Android sensor interrupts are enabled: 0-31 + _device._enabled_Android_intr_1 = 0; // Keep track of which Android sensor interrupts are enabled: 32- + + // Perform default startup + // Do a minimal startupDefault if using the DMP. User can always call startupDefault(false) manually if required. + status = startupDefault(_device._dmp_firmware_available); + if (status != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948_I2C::begin: startupDefault returned: ")); + debugPrintStatus(status); + debugPrintln(F("")); + } + return status; +} + +ICM_20948_Status_e ICM_20948::startupMagnetometer(bool minimal) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + i2cMasterPassthrough(false); //Do not connect the SDA/SCL pins to AUX_DA/AUX_CL + i2cMasterEnable(true); + + resetMag(); + + //After a ICM reset the Mag sensor may stop responding over the I2C master + //Reset the Master I2C until it responds + uint8_t tries = 0; + while (tries < MAX_MAGNETOMETER_STARTS) + { + tries++; + + //See if we can read the WhoIAm register correctly + retval = magWhoIAm(); + if (retval == ICM_20948_Stat_Ok) + break; //WIA matched! + + i2cMasterReset(); //Otherwise, reset the master I2C and try again + + delay(10); + } + + if (tries == MAX_MAGNETOMETER_STARTS) + { + debugPrint(F("ICM_20948::startupMagnetometer: reached MAX_MAGNETOMETER_STARTS (")); + debugPrintf((int)MAX_MAGNETOMETER_STARTS); + debugPrintln(F("). Returning ICM_20948_Stat_WrongID")); + status = ICM_20948_Stat_WrongID; + return status; + } + else + { + debugPrint(F("ICM_20948::startupMagnetometer: successful magWhoIAm after ")); + debugPrintf((int)tries); + if (tries == 1) + debugPrintln(F(" try")); + else + debugPrintln(F(" tries")); + } + + //Return now if minimal is true. The mag will be configured manually for the DMP + if (minimal) // Return now if minimal is true + { + debugPrintln(F("ICM_20948::startupMagnetometer: minimal startup complete!")); + return status; + } + + //Set up magnetometer + AK09916_CNTL2_Reg_t reg; + reg.MODE = AK09916_mode_cont_100hz; + reg.reserved_0 = 0; // Make sure the unused bits are clear. Probably redundant, but prevents confusion when looking at the I2C traffic + retval = writeMag(AK09916_REG_CNTL2, (uint8_t *)®); + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupMagnetometer: writeMag returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + + retval = i2cControllerConfigurePeripheral(0, MAG_AK09916_I2C_ADDR, AK09916_REG_ST1, 9, true, true, false, false, false); + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupMagnetometer: i2cMasterConfigurePeripheral returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + + return status; +} + +ICM_20948_Status_e ICM_20948::magWhoIAm(void) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + uint8_t whoiam1, whoiam2; + whoiam1 = readMag(AK09916_REG_WIA1); + // readMag calls i2cMasterSingleR which calls ICM_20948_i2c_master_single_r + // i2cMasterSingleR updates status so it is OK to set retval to status here + retval = status; + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::magWhoIAm: whoiam1: ")); + debugPrintf((int)whoiam1); + debugPrint(F(" (should be 72) readMag set status to: ")); + debugPrintStatus(status); + debugPrintln(F("")); + return retval; + } + whoiam2 = readMag(AK09916_REG_WIA2); + // readMag calls i2cMasterSingleR which calls ICM_20948_i2c_master_single_r + // i2cMasterSingleR updates status so it is OK to set retval to status here + retval = status; + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::magWhoIAm: whoiam1: ")); + debugPrintf((int)whoiam1); + debugPrint(F(" (should be 72) whoiam2: ")); + debugPrintf((int)whoiam2); + debugPrint(F(" (should be 9) readMag set status to: ")); + debugPrintStatus(status); + debugPrintln(F("")); + return retval; + } + + if ((whoiam1 == (MAG_AK09916_WHO_AM_I >> 8)) && (whoiam2 == (MAG_AK09916_WHO_AM_I & 0xFF))) + { + retval = ICM_20948_Stat_Ok; + status = retval; + return status; + } + + debugPrint(F("ICM_20948::magWhoIAm: whoiam1: ")); + debugPrintf((int)whoiam1); + debugPrint(F(" (should be 72) whoiam2: ")); + debugPrintf((int)whoiam2); + debugPrintln(F(" (should be 9). Returning ICM_20948_Stat_WrongID")); + + retval = ICM_20948_Stat_WrongID; + status = retval; + return status; +} + +// SPI + +// SPISettings ICM_20948_SPI_DEFAULT_SETTINGS(ICM_20948_SPI_DEFAULT_FREQ, ICM_20948_SPI_DEFAULT_ORDER, ICM_20948_SPI_DEFAULT_MODE); + +ICM_20948_SPI::ICM_20948_SPI() +{ +} + +ICM_20948_Status_e ICM_20948_SPI::begin(uint8_t csPin, SPIClass &spiPort, uint32_t SPIFreq) +{ + if (SPIFreq > 7000000) + SPIFreq = 7000000; // Limit SPI frequency to 7MHz + + // Associate + _spi = &spiPort; + _spisettings = SPISettings(SPIFreq, ICM_20948_SPI_DEFAULT_ORDER, ICM_20948_SPI_DEFAULT_MODE); + _cs = csPin; + + // Set pinmodes + pinMode(_cs, OUTPUT); + + // Set pins to default positions + digitalWrite(_cs, HIGH); + + // _spi->begin(); // Moved into user's sketch + + // 'Kickstart' the SPI hardware. + _spi->beginTransaction(_spisettings); + _spi->transfer(0x00); + _spi->endTransaction(); + + // Set up the serif + _serif.write = ICM_20948_write_SPI; + _serif.read = ICM_20948_read_SPI; + _serif.user = (void *)this; // refer to yourself in the user field + + // Link the serif + _device._serif = &_serif; + +#if defined(ICM_20948_USE_DMP) + _device._dmp_firmware_available = true; // Initialize _dmp_firmware_available +#else + _device._dmp_firmware_available = false; // Initialize _dmp_firmware_available +#endif + + _device._firmware_loaded = false; // Initialize _firmware_loaded + _device._last_bank = 255; // Initialize _last_bank. Make it invalid. It will be set by the first call of ICM_20948_set_bank. + _device._last_mems_bank = 255; // Initialize _last_mems_bank. Make it invalid. It will be set by the first call of inv_icm20948_write_mems. + _device._gyroSF = 0; // Use this to record the GyroSF, calculated by inv_icm20948_set_gyro_sf + _device._gyroSFpll = 0; + _device._enabled_Android_0 = 0; // Keep track of which Android sensors are enabled: 0-31 + _device._enabled_Android_1 = 0; // Keep track of which Android sensors are enabled: 32- + _device._enabled_Android_intr_0 = 0; // Keep track of which Android sensor interrupts are enabled: 0-31 + _device._enabled_Android_intr_1 = 0; // Keep track of which Android sensor interrupts are enabled: 32- + + // Perform default startup + // Do a minimal startupDefault if using the DMP. User can always call startupDefault(false) manually if required. + status = startupDefault(_device._dmp_firmware_available); + if (status != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948_SPI::begin: startupDefault returned: ")); + debugPrintStatus(status); + debugPrintln(F("")); + } + + return status; +} + +// serif functions for the I2C and SPI classes +ICM_20948_Status_e ICM_20948_write_I2C(uint8_t reg, uint8_t *data, uint32_t len, void *user) +{ + if (user == NULL) + { + return ICM_20948_Stat_ParamErr; + } + TwoWire *_i2c = ((ICM_20948_I2C *)user)->_i2c; // Cast user field to ICM_20948_I2C type and extract the I2C interface pointer + uint8_t addr = ((ICM_20948_I2C *)user)->_addr; + if (_i2c == NULL) + { + return ICM_20948_Stat_ParamErr; + } + + _i2c->beginTransmission(addr); + _i2c->write(reg); + _i2c->write(data, (uint8_t)len); + _i2c->endTransmission(); + + // for( uint32_t indi = 0; indi < len; indi++ ){ + // _i2c->beginTransmission(addr); + // _i2c->write(reg + indi); + // _i2c->write(*(data + indi) ); + // _i2c->endTransmission(); + // delay(10); + // } + + // delay(10); + + return ICM_20948_Stat_Ok; +} + +ICM_20948_Status_e ICM_20948_read_I2C(uint8_t reg, uint8_t *buff, uint32_t len, void *user) +{ + if (user == NULL) + { + return ICM_20948_Stat_ParamErr; + } + TwoWire *_i2c = ((ICM_20948_I2C *)user)->_i2c; + uint8_t addr = ((ICM_20948_I2C *)user)->_addr; + if (_i2c == NULL) + { + return ICM_20948_Stat_ParamErr; + } + + _i2c->beginTransmission(addr); + _i2c->write(reg); + _i2c->endTransmission(false); // Send repeated start + + uint32_t num_received = _i2c->requestFrom(addr, len); + + if (num_received == len) + { + for (uint8_t i = 0; i < len; i++) + { + buff[i] = _i2c->read(); + } + return ICM_20948_Stat_Ok; + } + else + { + return ICM_20948_Stat_NoData; + } + + if (len != 0) + { + return ICM_20948_Stat_NoData; + } + return ICM_20948_Stat_Ok; +} + +ICM_20948_Status_e ICM_20948_write_SPI(uint8_t reg, uint8_t *data, uint32_t len, void *user) +{ + if (user == NULL) + { + return ICM_20948_Stat_ParamErr; + } + SPIClass *_spi = ((ICM_20948_SPI *)user)->_spi; // Cast user field to ICM_20948_SPI type and extract the SPI interface pointer + uint8_t cs = ((ICM_20948_SPI *)user)->_cs; + SPISettings spisettings = ((ICM_20948_SPI *)user)->_spisettings; + if (_spi == NULL) + { + return ICM_20948_Stat_ParamErr; + } + + // 'Kickstart' the SPI hardware. This is a fairly high amount of overhead, but it guarantees that the lines will start in the correct states even when sharing the SPI bus with devices that use other modes + _spi->beginTransaction(spisettings); + _spi->transfer(0x00); + _spi->endTransaction(); + + _spi->beginTransaction(spisettings); + digitalWrite(cs, LOW); + // delayMicroseconds(5); + _spi->transfer(((reg & 0x7F) | 0x00)); + // SPI.transfer(data, len); // Can't do this thanks to Arduino's poor implementation + for (uint32_t indi = 0; indi < len; indi++) + { + _spi->transfer(*(data + indi)); + } + // delayMicroseconds(5); + digitalWrite(cs, HIGH); + _spi->endTransaction(); + + return ICM_20948_Stat_Ok; +} + +ICM_20948_Status_e ICM_20948_read_SPI(uint8_t reg, uint8_t *buff, uint32_t len, void *user) +{ + if (user == NULL) + { + return ICM_20948_Stat_ParamErr; + } + SPIClass *_spi = ((ICM_20948_SPI *)user)->_spi; + uint8_t cs = ((ICM_20948_SPI *)user)->_cs; + SPISettings spisettings = ((ICM_20948_SPI *)user)->_spisettings; + if (_spi == NULL) + { + return ICM_20948_Stat_ParamErr; + } + + // 'Kickstart' the SPI hardware. This is a fairly high amount of overhead, but it guarantees that the lines will start in the correct states + _spi->beginTransaction(spisettings); + _spi->transfer(0x00); + _spi->endTransaction(); + + _spi->beginTransaction(spisettings); + digitalWrite(cs, LOW); + // delayMicroseconds(5); + _spi->transfer(((reg & 0x7F) | 0x80)); + // SPI.transfer(data, len); // Can't do this thanks to Arduino's stupid implementation + for (uint32_t indi = 0; indi < len; indi++) + { + *(buff + indi) = _spi->transfer(0x00); + } + // delayMicroseconds(5); + digitalWrite(cs, HIGH); + _spi->endTransaction(); + + return ICM_20948_Stat_Ok; +} + + diff --git a/src/ICM_20948.h b/src/ICM_20948.h new file mode 100644 index 0000000..1ec9259 --- /dev/null +++ b/src/ICM_20948.h @@ -0,0 +1,289 @@ +/* + +A C++ interface to the ICM-20948 + +*/ + +#ifndef _ICM_20948_H_ +#define _ICM_20948_H_ + +extern "C" { + #include "util/ICM_20948_C.h" // The C backbone. ICM_20948_USE_DMP is defined in here. +} + +#include "util/AK09916_REGISTERS.h" + +#include "Arduino.h" // Arduino support +#include "Wire.h" +#include "SPI.h" + +#define ICM_20948_ARD_UNUSED_PIN 0xFF + +// Base +class ICM_20948 +{ +private: + Stream *_debugSerial; //The stream to send debug messages to if enabled + bool _printDebug = false; //Flag to print the serial commands we are sending to the Serial port for debug + + const uint8_t MAX_MAGNETOMETER_STARTS = 10; // This replaces maxTries + +protected: + ICM_20948_Device_t _device; + + float getTempC(int16_t val); + float getGyrDPS(int16_t axis_val); + float getAccMG(int16_t axis_val); + float getMagUT(int16_t axis_val); + +public: + ICM_20948(); // Constructor + +// Enable debug messages using the chosen Serial port (Stream) +// Boards like the RedBoard Turbo use SerialUSB (not Serial). +// But other boards like the SAMD51 Thing Plus use Serial (not SerialUSB). +// These lines let the code compile cleanly on as many SAMD boards as possible. +#if defined(ARDUINO_ARCH_SAMD) // Is this a SAMD board? +#if defined(USB_VID) // Is the USB Vendor ID defined? +#if (USB_VID == 0x1B4F) // Is this a SparkFun board? +#if !defined(ARDUINO_SAMD51_THING_PLUS) & !defined(ARDUINO_SAMD51_MICROMOD) // If it is not a SAMD51 Thing Plus or SAMD51 MicroMod + void enableDebugging(Stream &debugPort = SerialUSB); //Given a port to print to, enable debug messages. +#else + void enableDebugging(Stream &debugPort = Serial); //Given a port to print to, enable debug messages. +#endif +#else + void enableDebugging(Stream &debugPort = Serial); //Given a port to print to, enable debug messages. +#endif +#else + void enableDebugging(Stream &debugPort = Serial); //Given a port to print to, enable debug messages. +#endif +#else + void enableDebugging(Stream &debugPort = Serial); //Given a port to print to, enable debug messages. +#endif + + void disableDebugging(void); //Turn off debug statements + + void debugPrintStatus(ICM_20948_Status_e stat); + + // gfvalvo's flash string helper code: https://forum.arduino.cc/index.php?topic=533118.msg3634809#msg3634809 + void debugPrint(const char *); + void debugPrint(const __FlashStringHelper *); + void debugPrintln(const char *); + void debugPrintln(const __FlashStringHelper *); + void doDebugPrint(char (*)(const char *), const char *, bool newLine = false); + + void debugPrintf(int i); + void debugPrintf(float f); + + ICM_20948_AGMT_t agmt; // Acceleometer, Gyroscope, Magenetometer, and Temperature data + ICM_20948_AGMT_t getAGMT(void); // Updates the agmt field in the object and also returns a copy directly + + float magX(void); // micro teslas + float magY(void); // micro teslas + float magZ(void); // micro teslas + + float accX(void); // milli g's + float accY(void); // milli g's + float accZ(void); // milli g's + + float gyrX(void); // degrees per second + float gyrY(void); // degrees per second + float gyrZ(void); // degrees per second + + float temp(void); // degrees celsius + + ICM_20948_Status_e status; // Status from latest operation + const char *statusString(ICM_20948_Status_e stat = ICM_20948_Stat_NUM); // Returns a human-readable status message. Defaults to status member, but prints string for supplied status if supplied + + // Device Level + ICM_20948_Status_e setBank(uint8_t bank); // Sets the bank + ICM_20948_Status_e swReset(void); // Performs a SW reset + ICM_20948_Status_e sleep(bool on = false); // Set sleep mode for the chip + ICM_20948_Status_e lowPower(bool on = true); // Set low power mode for the chip + ICM_20948_Status_e setClockSource(ICM_20948_PWR_MGMT_1_CLKSEL_e source); // Choose clock source + ICM_20948_Status_e checkID(void); // Return 'ICM_20948_Stat_Ok' if whoami matches ICM_20948_WHOAMI + + bool dataReady(void); // Returns 'true' if data is ready + uint8_t getWhoAmI(void); // Return whoami in out prarmeter + bool isConnected(void); // Returns true if communications with the device are sucessful + + // Internal Sensor Options + ICM_20948_Status_e setSampleMode(uint8_t sensor_id_bm, uint8_t lp_config_cycle_mode); // Use to set accel, gyro, and I2C master into cycled or continuous modes + ICM_20948_Status_e setFullScale(uint8_t sensor_id_bm, ICM_20948_fss_t fss); + ICM_20948_Status_e setDLPFcfg(uint8_t sensor_id_bm, ICM_20948_dlpcfg_t cfg); + ICM_20948_Status_e enableDLPF(uint8_t sensor_id_bm, bool enable); + ICM_20948_Status_e setSampleRate(uint8_t sensor_id_bm, ICM_20948_smplrt_t smplrt); + + // Interrupts on INT and FSYNC Pins + ICM_20948_Status_e clearInterrupts(void); + + ICM_20948_Status_e cfgIntActiveLow(bool active_low); + ICM_20948_Status_e cfgIntOpenDrain(bool open_drain); + ICM_20948_Status_e cfgIntLatch(bool latching); // If not latching then the interrupt is a 50 us pulse + ICM_20948_Status_e cfgIntAnyReadToClear(bool enabled); // If enabled, *ANY* read will clear the INT_STATUS register. So if you have multiple interrupt sources enabled be sure to read INT_STATUS first + ICM_20948_Status_e cfgFsyncActiveLow(bool active_low); + ICM_20948_Status_e cfgFsyncIntMode(bool interrupt_mode); // Can use FSYNC as an interrupt input that sets the I2C Master Status register's PASS_THROUGH bit + + ICM_20948_Status_e intEnableI2C(bool enable); + ICM_20948_Status_e intEnableDMP(bool enable); + ICM_20948_Status_e intEnablePLL(bool enable); + ICM_20948_Status_e intEnableWOM(bool enable); + ICM_20948_Status_e intEnableWOF(bool enable); + ICM_20948_Status_e intEnableRawDataReady(bool enable); + ICM_20948_Status_e intEnableOverflowFIFO(uint8_t bm_enable); + ICM_20948_Status_e intEnableWatermarkFIFO(uint8_t bm_enable); + + ICM_20948_Status_e WOMThreshold(uint8_t threshold); + + // Interface Options + ICM_20948_Status_e i2cMasterPassthrough(bool passthrough = true); + ICM_20948_Status_e i2cMasterEnable(bool enable = true); + ICM_20948_Status_e i2cMasterReset(); + + //Used for configuring peripherals 0-3 + ICM_20948_Status_e i2cControllerConfigurePeripheral(uint8_t peripheral, uint8_t addr, uint8_t reg, uint8_t len, bool Rw = true, bool enable = true, bool data_only = false, bool grp = false, bool swap = false, uint8_t dataOut = 0); + ICM_20948_Status_e i2cControllerPeriph4Transaction(uint8_t addr, uint8_t reg, uint8_t *data, uint8_t len, bool Rw, bool send_reg_addr = true); + + //Provided for backward-compatibility only. Please update to i2cControllerConfigurePeripheral and i2cControllerPeriph4Transaction. + //https://www.oshwa.org/2020/06/29/a-resolution-to-redefine-spi-pin-names/ + ICM_20948_Status_e i2cMasterConfigureSlave(uint8_t peripheral, uint8_t addr, uint8_t reg, uint8_t len, bool Rw = true, bool enable = true, bool data_only = false, bool grp = false, bool swap = false); + ICM_20948_Status_e i2cMasterSLV4Transaction(uint8_t addr, uint8_t reg, uint8_t *data, uint8_t len, bool Rw, bool send_reg_addr = true); + + //Used for configuring the Magnetometer + ICM_20948_Status_e i2cMasterSingleW(uint8_t addr, uint8_t reg, uint8_t data); + uint8_t i2cMasterSingleR(uint8_t addr, uint8_t reg); + + // Default Setup + ICM_20948_Status_e startupDefault(bool minimal = false); // If minimal is true, several startup steps are skipped. If ICM_20948_USE_DMP is defined, .begin will call startupDefault with minimal set to true. + + // direct read/write + ICM_20948_Status_e read(uint8_t reg, uint8_t *pdata, uint32_t len); + ICM_20948_Status_e write(uint8_t reg, uint8_t *pdata, uint32_t len); + + //Mag specific + ICM_20948_Status_e startupMagnetometer(bool minimal = false); // If minimal is true, several startup steps are skipped. The mag then needs to be set up manually for the DMP. + ICM_20948_Status_e magWhoIAm(void); + uint8_t readMag(AK09916_Reg_Addr_e reg); + ICM_20948_Status_e writeMag(AK09916_Reg_Addr_e reg, uint8_t *pdata); + ICM_20948_Status_e resetMag(); + + //FIFO + ICM_20948_Status_e enableFIFO(bool enable = true); + ICM_20948_Status_e resetFIFO(void); + ICM_20948_Status_e setFIFOmode(bool snapshot = false); // Default to Stream (non-Snapshot) mode + ICM_20948_Status_e getFIFOcount(uint16_t *count); + ICM_20948_Status_e readFIFO(uint8_t *data, uint8_t len = 1); + + //DMP + + //Gyro Bias + ICM_20948_Status_e setBiasGyroX(int32_t newValue); + ICM_20948_Status_e setBiasGyroY(int32_t newValue); + ICM_20948_Status_e setBiasGyroZ(int32_t newValue); + ICM_20948_Status_e getBiasGyroX(int32_t* bias); + ICM_20948_Status_e getBiasGyroY(int32_t* bias); + ICM_20948_Status_e getBiasGyroZ(int32_t* bias); + //Accel Bias + ICM_20948_Status_e setBiasAccelX(int32_t newValue); + ICM_20948_Status_e setBiasAccelY(int32_t newValue); + ICM_20948_Status_e setBiasAccelZ(int32_t newValue); + ICM_20948_Status_e getBiasAccelX(int32_t* bias); + ICM_20948_Status_e getBiasAccelY(int32_t* bias); + ICM_20948_Status_e getBiasAccelZ(int32_t* bias); + //CPass Bias + ICM_20948_Status_e setBiasCPassX(int32_t newValue); + ICM_20948_Status_e setBiasCPassY(int32_t newValue); + ICM_20948_Status_e setBiasCPassZ(int32_t newValue); + ICM_20948_Status_e getBiasCPassX(int32_t* bias); + ICM_20948_Status_e getBiasCPassY(int32_t* bias); + ICM_20948_Status_e getBiasCPassZ(int32_t* bias); + + // Done: + // Configure DMP start address through PRGM_STRT_ADDRH/PRGM_STRT_ADDRL + // Load Firmware + // Configure Accel scaling to DMP + // Configure Compass mount matrix and scale to DMP + // Reset FIFO + // Reset DMP + // Enable DMP interrupt + // Configuring DMP to output data to FIFO: set DATA_OUT_CTL1, DATA_OUT_CTL2, DATA_INTR_CTL and MOTION_EVENT_CTL + // Configuring DMP to output data at multiple ODRs + // Configure DATA_RDY_STATUS + // Configuring Accel calibration + // Configuring Compass calibration + // Configuring Gyro gain + // Configuring Accel gain + // Configure I2C_SLV0 and I2C_SLV1 to: request mag data from the hidden reserved AK09916 registers; trigger Single Measurements + // Configure I2C Master ODR (default to 68.75Hz) + + // To Do: + // Additional FIFO output control: FIFO_WATERMARK, BM_BATCH_MASK, BM_BATCH_CNTR, BM_BATCH_THLD + // Configuring DMP features: PED_STD_STEPCTR, PED_STD_TIMECTR + // Enabling Activity Recognition (BAC) feature + // Enabling Significant Motion Detect (SMD) feature + // Enabling Tilt Detector feature + // Enabling Pick Up Gesture feature + // Enabling Fsync detection feature + // Biases: add save and load methods + + ICM_20948_Status_e enableDMP(bool enable = true); + ICM_20948_Status_e resetDMP(void); + ICM_20948_Status_e loadDMPFirmware(void); + ICM_20948_Status_e setDMPstartAddress(unsigned short address = DMP_START_ADDRESS); + ICM_20948_Status_e enableDMPSensor(enum inv_icm20948_sensor sensor, bool enable = true); + ICM_20948_Status_e enableDMPSensorInt(enum inv_icm20948_sensor sensor, bool enable = true); + ICM_20948_Status_e writeDMPmems(unsigned short reg, unsigned int length, const unsigned char *data); + ICM_20948_Status_e readDMPmems(unsigned short reg, unsigned int length, unsigned char *data); + ICM_20948_Status_e setDMPODRrate(enum DMP_ODR_Registers odr_reg, int interval); + ICM_20948_Status_e readDMPdataFromFIFO(icm_20948_DMP_data_t *data); + ICM_20948_Status_e setGyroSF(unsigned char div, int gyro_level); + ICM_20948_Status_e initializeDMP(void) __attribute__((weak)); // Combine all of the DMP start-up code in one place. Can be overwritten if required +}; + +// I2C + +// Forward declarations of TwoWire and Wire for board/variant combinations that don't have a default 'SPI' +//class TwoWire; // Commented by PaulZC 21/2/8 - this was causing compilation to fail on the Arduino NANO 33 BLE +//extern TwoWire Wire; // Commented by PaulZC 21/2/8 - this was causing compilation to fail on the Arduino NANO 33 BLE + +class ICM_20948_I2C : public ICM_20948 +{ +private: +protected: +public: + TwoWire *_i2c; + uint8_t _addr; + uint8_t _ad0; + bool _ad0val; + ICM_20948_Serif_t _serif; + + ICM_20948_I2C(); // Constructor + + virtual ICM_20948_Status_e begin(TwoWire &wirePort = Wire, bool ad0val = true, uint8_t ad0pin = ICM_20948_ARD_UNUSED_PIN); +}; + +// SPI +#define ICM_20948_SPI_DEFAULT_FREQ 4000000 +#define ICM_20948_SPI_DEFAULT_ORDER MSBFIRST +#define ICM_20948_SPI_DEFAULT_MODE SPI_MODE0 + +// Forward declarations of SPIClass and SPI for board/variant combinations that don't have a default 'SPI' +//class SPIClass; // Commented by PaulZC 21/2/8 - this was causing compilation to fail on the Arduino NANO 33 BLE +//extern SPIClass SPI; // Commented by PaulZC 21/2/8 - this was causing compilation to fail on the Arduino NANO 33 BLE + +class ICM_20948_SPI : public ICM_20948 +{ +private: +protected: +public: + SPIClass *_spi; + SPISettings _spisettings; + uint8_t _cs; + ICM_20948_Serif_t _serif; + + ICM_20948_SPI(); // Constructor + + ICM_20948_Status_e begin(uint8_t csPin, SPIClass &spiPort = SPI, uint32_t SPIFreq = ICM_20948_SPI_DEFAULT_FREQ); +}; + +#endif /* _ICM_20948_H_ */ diff --git a/src/main.cpp b/src/main.cpp index 7b9e27d..7db5c1f 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -6,6 +6,7 @@ */ #include #include +#include "ICM_20948.h" /* Brakelight config */ #define PIN_BRAKELIGHT 6 /* Digital output used to enable the brakelight */ @@ -13,6 +14,13 @@ #define BRAKELIGHT_OFF 0b0 #define BPPS_THRESHOLD 10 /* Threshold that BPPS needs to have to be considered as braking */ +/* IMU config */ +#define ICM_AD0_VAL 1 /* The last bit of the IMU address on the I2C bus (default) */ +#define ICM_I2C_CLOCK 1 /* The clock speed of the I2C bus */ +ICM_20948_I2C icm; +#define ICM_DATA_PERIOD 100 /* Time between polling and publishing of IMU data */ +uint64_t time_last_icm_data = 0; + /* Invertor config */ #define MC_L_ID 0x4F /* ID of the left invertor, to be used in CAN communication */ #define MC_R_ID 0x4F /* ID of the right invertor, to be used in CAN communication */ @@ -42,11 +50,16 @@ uint64_t time_last_heartbeat = 0; /* Timestamp of last heartbeat message t /* CAN config continued */ #define CAN_ID_CRITICAL_FAULT 0x000 /* CAN ID of critical fault message (not using any Module ID) */ +#define CAN_ID_GENERAL_FAULT 0x020 /* CAN ID of general fault message (not using any Module ID) */ #define CAN_ID_APPS_BPPS 0x110 /* CAN ID of APPS and BPPS values (not using Module ID of APPS/BPPS) */ #define CAN_ID_BOOT_SEQ 0x090 /* CAN ID of Boot Sequence Status (for RTD) values (using Module ID of ECU for safety) */ #define CAN_ID_TC_INFO_GEN 0x480 /* CAN ID of TC general information */ #define CAN_ID_TC_INFO_ERPM 0x490 /* CAN ID of TC ERPM information */ #define CAN_ID_TC_INFO_TEMP 0x4A0 /* CAN ID of TC temperature information */ +#define CAN_ID_IMU_ACC 0x580 /* CAN ID of IMU acceleration information */ +#define CAN_ID_IMU_GYRO 0x590 /* CAN ID of IMU gyroscope information */ +#define CAN_ID_IMU_MAGN 0x5A0 /* CAN ID of IMU magnetometer information */ +#define CAN_ID_IMU_TEMP 0x5B0 /* CAN ID of IMU temperature information */ /* Torque Controller variables */ #define TC_OK 0b0 @@ -111,6 +124,7 @@ uint32_t time_last_can_fault_send = 0; #define FAULT_RTD_TIMEOUT 0x11 /* Did not receive RTD state in short enough time, assume data loss */ #define FAULT_APPS_BPPS_TIMEOUT 0x12 /* Did not receive APPS/BPPS values in short enough time, assume data loss */ #define FAULT_INV_TIMEOUT 0x13 /* Did not receive INV values in short enough time, assume data loss */ +#define FAULT_IMU_ERROR 0x14 /* Something wrong with IMU, non-critical */ /* SAFETY */ void enter_safe_state(char fault_id) { @@ -426,11 +440,99 @@ void update_brakelight() { digitalWrite(PIN_BRAKELIGHT, output); } +/* IMU */ +void setup_imu() { + uint8_t count = 0; + do { + /* Init I2C */ + Wire.begin(); + Wire.setClock(ICM_I2C_CLOCK); + + /* Init IMU */ + icm.begin(Wire, ICM_AD0_VAL); + + /* Send CAN message */ + CAN_message_t m; + m.id = CAN_ID_GENERAL_FAULT | CAN_MODULE_ID; + m.buf[0] = CAN_FAULT_ID; + m.buf[1] = FAULT_IMU_ERROR; + can_lv.write(m); + + /* Wait a bit */ + delay(500); + count++; + } + while ((icm.status != ICM_20948_Stat_Ok) && (count < 3)); +} + +void update_imu() { + /* Check if new data */ + if (icm.dataReady()) { + /* Rate limiting */ + if (millis() < time_last_icm_data + ICM_DATA_PERIOD) return; + + /* Update values */ + icm.getAGMT(); + int16_t acc_x = (int16_t) icm.accX(); + int16_t acc_y = (int16_t) icm.accY(); + int16_t acc_z = (int16_t) icm.accZ(); + int16_t gyr_x = (int16_t) icm.gyrX(); + int16_t gyr_y = (int16_t) icm.gyrY(); + int16_t gyr_z = (int16_t) icm.gyrZ(); + int16_t mag_x = (int16_t) icm.magX(); + int16_t mag_y = (int16_t) icm.magY(); + int16_t mag_z = (int16_t) icm.magZ(); + int16_t temp = (int16_t) icm.temp(); + + /* Send to LV CAN */ + CAN_message_t m_acc; + m_acc.id = CAN_ID_IMU_ACC | CAN_MODULE_ID; + m_acc.buf[0] = (acc_x >> 8) & 0xff; + m_acc.buf[1] = acc_x & 0xff; + m_acc.buf[2] = (acc_y >> 8) & 0xff; + m_acc.buf[3] = acc_y & 0xff; + m_acc.buf[4] = (acc_z >> 8) & 0xff; + m_acc.buf[5] = acc_z & 0xff; + can_lv.write(m_acc); + + CAN_message_t m_gyr; + m_gyr.id = CAN_ID_IMU_GYRO | CAN_MODULE_ID; + m_gyr.buf[0] = (gyr_x >> 8) & 0xff; + m_gyr.buf[1] = gyr_x & 0xff; + m_gyr.buf[2] = (gyr_y >> 8) & 0xff; + m_gyr.buf[3] = gyr_y & 0xff; + m_gyr.buf[4] = (gyr_z >> 8) & 0xff; + m_gyr.buf[5] = gyr_z & 0xff; + can_lv.write(m_gyr); + + CAN_message_t m_mag; + m_mag.id = CAN_ID_IMU_MAGN | CAN_MODULE_ID; + m_mag.buf[0] = (mag_x >> 8) & 0xff; + m_mag.buf[1] = mag_x & 0xff; + m_mag.buf[2] = (mag_y >> 8) & 0xff; + m_mag.buf[3] = mag_y & 0xff; + m_mag.buf[4] = (mag_z >> 8) & 0xff; + m_mag.buf[5] = mag_z & 0xff; + can_lv.write(m_mag); + + CAN_message_t m_temp; + m_temp.id = CAN_ID_IMU_TEMP | CAN_MODULE_ID; + m_temp.buf[0] = (temp >> 8) & 0xff; + m_temp.buf[1] = temp & 0xff; + can_lv.write(m_temp); + + /* Update state */ + time_last_icm_data = millis(); + } +} + + /* MAIN */ void setup() { /* Setup all required stuff */ can_setup(); /* Init CAN */ setup_brakelight(); /* Setup brakelight obviously */ + setup_imu(); /* Establish connection to IMU */ } void loop() { @@ -441,5 +543,6 @@ void loop() { update_brakelight(); /* Flashy shiny thingies */ analyse_drive_data(); /* Analyse the data from the drives duh */ update_drives(); /* Do motorcontroller shit */ + update_imu(); /* Get data from IMU */ } diff --git a/src/util/AK09916_ENUMERATIONS.h b/src/util/AK09916_ENUMERATIONS.h new file mode 100644 index 0000000..b62b7c3 --- /dev/null +++ b/src/util/AK09916_ENUMERATIONS.h @@ -0,0 +1,15 @@ +#ifndef _AK09916_ENUMERATIONS_H_ +#define _AK09916_ENUMERATIONS_H_ + +typedef enum +{ + AK09916_mode_power_down = 0x00, + AK09916_mode_single = (0x01 << 0), + AK09916_mode_cont_10hz = (0x01 << 1), + AK09916_mode_cont_20hz = (0x02 << 1), + AK09916_mode_cont_50hz = (0x03 << 1), + AK09916_mode_cont_100hz = (0x04 << 1), + AK09916_mode_self_test = (0x01 << 4), +} AK09916_mode_e; + +#endif // _AK09916_ENUMERATIONS_H_ \ No newline at end of file diff --git a/src/util/AK09916_REGISTERS.h b/src/util/AK09916_REGISTERS.h new file mode 100644 index 0000000..9c91c3c --- /dev/null +++ b/src/util/AK09916_REGISTERS.h @@ -0,0 +1,83 @@ +#ifndef _AK09916_REGISTERS_H_ +#define _AK09916_REGISTERS_H_ + +#include + +typedef enum +{ + AK09916_REG_WIA1 = 0x00, + AK09916_REG_WIA2, + AK09916_REG_RSV1, + AK09916_REG_RSV2, // Reserved register. We start reading here when using the DMP. Secret sauce... + // discontinuity - containing another nine reserved registers? Secret sauce... + AK09916_REG_ST1 = 0x10, + AK09916_REG_HXL, + AK09916_REG_HXH, + AK09916_REG_HYL, + AK09916_REG_HYH, + AK09916_REG_HZL, + AK09916_REG_HZH, + // discontinuity + AK09916_REG_ST2 = 0x18, + // discontinuity + AK09916_REG_CNTL2 = 0x31, + AK09916_REG_CNTL3, +} AK09916_Reg_Addr_e; + +typedef struct +{ + uint8_t WIA1; +} AK09916_WIA1_Reg_t; + +typedef struct +{ + uint8_t WIA2; +} AK09916_WIA2_Reg_t; + +typedef struct +{ + uint8_t DRDY : 1; + uint8_t DOR : 1; + uint8_t reserved_0 : 6; +} AK09916_ST1_Reg_t; + +// typedef struct{ + +// }AK09916_HXL_Reg_t; + +// typedef struct{ + +// }AK09916_HXH_Reg_t; +// typedef struct{ + +// }AK09916_HYL_Reg_t; +// typedef struct{ + +// }AK09916_HYH_Reg_t; +// typedef struct{ + +// }AK09916_HZL_Reg_t; +// typedef struct{ + +// }AK09916_HZH_Reg_t; + +typedef struct +{ + uint8_t reserved_0 : 3; + uint8_t HOFL : 1; + uint8_t reserved_1 : 4; +} AK09916_ST2_Reg_t; + +typedef struct +{ + uint8_t MODE : 5; + uint8_t reserved_0 : 3; +} AK09916_CNTL2_Reg_t; + +typedef struct +{ + uint8_t SRST : 1; + uint8_t reserved_0 : 7; +} AK09916_CNTL3_Reg_t; + +#endif // _AK09916_REGISTERS_H_ diff --git a/src/util/ICM20948_eMD_nucleo_1.0/icm20948_img.dmp3a.h_14290 b/src/util/ICM20948_eMD_nucleo_1.0/icm20948_img.dmp3a.h_14290 new file mode 100644 index 0000000..ca0dd48 --- /dev/null +++ b/src/util/ICM20948_eMD_nucleo_1.0/icm20948_img.dmp3a.h_14290 @@ -0,0 +1,951 @@ + /* bank # 0 */ + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x05, 0x00, 0x00, 0x00, 0x05, 0x00, 0x00, 0x00, 0x05, 0x00, 0x01, 0x00, 0x05, 0x00, 0xff, + 0xff, 0xf7, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, + 0x80, 0x00, 0x80, 0x00, 0x40, 0x00, 0x40, 0x00, 0x20, 0x00, 0x20, 0x00, 0x10, 0x00, 0x10, 0x00, + 0x08, 0x00, 0x08, 0x00, 0x04, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x00, 0x01, 0x00, 0x01, 0x00, + 0x00, 0x80, 0x00, 0x80, 0x00, 0x40, 0x00, 0x40, 0x00, 0x20, 0x00, 0x20, 0x00, 0x10, 0x00, 0x10, + 0x00, 0x08, 0x00, 0x08, 0x00, 0x04, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x00, 0x01, 0x00, 0x01, + /* bank # 1 */ + 0x00, 0x00, 0x03, 0x84, 0x00, 0x00, 0x9c, 0x40, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, + 0x36, 0x66, 0x66, 0x66, 0x00, 0x0f, 0x00, 0x00, 0x13, 0x5c, 0x28, 0xf6, 0x0c, 0xf5, 0xc2, 0x8f, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xff, 0xf8, 0x00, 0x38, + 0x04, 0xf6, 0xe8, 0xf4, 0x00, 0x00, 0x68, 0x00, 0x00, 0x01, 0xff, 0xc7, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x01, 0x47, 0xae, 0x14, 0x3e, 0xb8, 0x51, 0xec, 0x00, 0x0f, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x0c, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x15, 0x55, 0x55, 0x55, 0x0a, 0xaa, 0xaa, 0xaa, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe1, 0x00, 0x00, 0x00, 0x01, 0x00, 0x06, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x48, 0xd1, 0x59, 0x3f, 0xb7, 0x2e, 0xa7, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x8e, 0x17, 0x00, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x20, + /* bank # 2 */ + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7f, 0xff, 0x00, 0x00, 0x00, 0x05, 0x21, 0xe9, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x3e, 0x03, 0x30, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x03, 0x00, 0x0a, 0x01, 0x2b, 0x4a, 0xee, + 0x06, 0x54, 0xad, 0x11, 0xe3, 0x07, 0x5c, 0x15, 0x36, 0x2b, 0xd0, 0x26, 0xd0, 0x8c, 0x49, 0xa4, + 0x06, 0x54, 0xad, 0x11, 0x1e, 0x0b, 0xb5, 0x55, 0x38, 0xee, 0x17, 0x50, 0x31, 0x36, 0x3f, 0x03, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 3 */ + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x80, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x00, 0x00, 0x0e, 0x35, 0x75, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x10, 0x00, 0x96, 0x00, 0x3c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0d, 0x72, 0xaa, 0x29, 0xc9, 0x3d, 0x6c, 0x4e, 0x55, 0x16, 0x4c, 0x7f, 0xc4, 0x42, 0x74, 0x97, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x3d, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x31, 0x88, 0x15, 0xe3, 0xa3, 0x40, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0e, 0x70, 0x4b, 0x8c, 0xc5, 0x0a, 0x92, 0xbe, 0x5a, 0x96, 0x91, 0xd2, 0xc1, 0xee, 0xe7, 0x0d, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x02, + 0x00, 0x00, 0x00, 0x14, 0x00, 0x2d, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 4 */ + 0x00, 0x00, 0x00, 0xa3, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x3a, 0x03, 0xe8, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x26, 0x00, 0x00, 0x00, 0x02, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x3f, 0xc1, 0xa7, 0x68, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x33, 0x33, 0x33, 0x33, 0x0c, 0xcc, 0xcc, 0xcd, + 0x00, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x18, + 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0xff, 0x00, 0x00, 0x80, 0x00, 0x20, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x64, 0x87, 0xed, 0x51, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x64, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x01, 0x1d, 0xf4, 0x6a, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x02, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x00, 0x7f, 0xff, 0x00, 0x00, 0x20, 0x00, + /* bank # 5 */ + 0x00, 0x00, 0x9c, 0x40, 0x0c, 0xcc, 0xcc, 0xcd, 0x00, 0x00, 0x07, 0x80, 0x00, 0x02, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3e, 0xb8, 0x51, 0xec, 0x01, 0x47, 0xae, 0x14, + 0x00, 0x00, 0x01, 0x5e, 0x00, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x10, 0x00, 0x00, + 0x00, 0x00, 0x61, 0xa8, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x10, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, 0x2e, 0xe0, 0x00, 0x06, 0x40, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, + 0x03, 0xff, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x33, 0x33, 0x33, 0x33, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0c, 0xcc, 0xcc, 0xcd, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x9d, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 6 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x49, 0x1b, 0x75, + 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x40, 0x00, 0x00, 0x0c, 0xcd, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 7 */ + 0x00, 0x00, 0x50, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x16, 0x00, 0x00, 0x00, 0x00, 0x46, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xd4, 0xc0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, 0x01, 0x3c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 8 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x28, 0x00, 0x00, 0x3a, 0x98, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x01, 0x4e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x47, 0xae, 0x14, 0x4e, 0x40, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0c, 0x00, 0x00, 0x20, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0d, 0x06, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x27, 0x10, + 0x00, 0x00, 0x00, 0x00, 0x4a, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0e, 0xd8, 0x00, 0x00, 0x01, 0x18, 0x00, 0x00, 0x07, 0xd0, + /* bank # 9 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x27, 0x10, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x13, 0x1b, + 0x00, 0x0b, 0xb8, 0x00, 0x00, 0x3c, 0xbf, 0x0f, 0x00, 0x55, 0xce, 0x75, 0x00, 0x00, 0x27, 0x10, + 0x05, 0xb0, 0x5b, 0x05, 0x3a, 0x4f, 0xa4, 0xfa, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x00, 0x00, 0x00, 0x3c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5a, 0x00, 0x1d, 0x20, 0x8a, 0x00, 0x61, 0x93, 0x69, + 0x00, 0x00, 0x01, 0x3c, 0x00, 0x00, 0x4d, 0xf0, 0x00, 0x55, 0xce, 0x75, 0x00, 0x00, 0x02, 0x76, + 0x06, 0x66, 0x66, 0x66, 0x39, 0x99, 0x99, 0x99, 0x10, 0x00, 0x00, 0x00, 0x30, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x0c, 0xcc, 0xcc, 0xcc, 0x33, 0x33, 0x33, 0x33, 0x00, 0x0e, 0x90, 0x45, + 0x00, 0x00, 0x00, 0x00, 0x01, 0xd4, 0x1d, 0x41, 0x3e, 0x2b, 0xe2, 0xbf, 0x3f, 0xf1, 0x6f, 0xbb, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x93, 0x87, 0x00, 0x01, 0x24, 0x92, 0x49, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x13, 0x88, 0x00, 0x98, 0x96, 0x80, 0x08, 0x58, 0x3b, 0x00, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0e, 0xaf, 0x00, 0x00, 0x17, 0x70, 0x00, 0x00, 0x00, 0x01, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 10 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, + 0x3f, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x33, 0x33, 0x33, 0x00, 0x1c, 0xfa, 0x77, + 0x0c, 0x6d, 0x39, 0xe6, 0xcb, 0x6f, 0xda, 0xa6, 0x53, 0xcf, 0xd3, 0x97, 0xc4, 0x53, 0x74, 0x46, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xda, 0x74, 0x0e, 0x3f, 0x25, 0x8b, 0xf2, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x1d, 0x4c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 11 */ + 0x20, 0x00, 0x00, 0x00, 0x3e, 0x2b, 0xe2, 0xbf, 0x3e, 0x14, 0x7a, 0xe2, 0x30, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x13, 0x88, 0x00, 0x00, 0x07, 0xd0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x13, 0x88, 0x3c, 0x23, 0xec, 0x84, + 0x20, 0x00, 0x00, 0x00, 0x01, 0xd4, 0x1d, 0x41, 0x01, 0xeb, 0x85, 0x1e, 0x10, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x13, 0x88, 0x00, 0x00, 0x00, 0x00, 0x34, 0x6c, 0xfc, 0xb2, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, + 0x00, 0x00, 0x17, 0x70, 0x00, 0x00, 0x13, 0x88, 0x00, 0x00, 0x23, 0x28, 0x00, 0x00, 0x00, 0x26, + 0x00, 0x00, 0x00, 0x2f, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x09, 0xc4, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x23, 0x01, 0xeb, 0x85, 0x1e, 0x3e, 0x14, 0x7a, 0xe2, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x2d, 0x02, 0x22, 0x22, 0x22, 0x3d, 0xdd, 0xdd, 0xde, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x24, 0xb8, 0x3d, 0xd1, 0xba, 0x8e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 12 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x83, 0xd6, 0x00, 0x00, 0x83, 0xd6, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, 0x21, + 0x00, 0x20, 0x00, 0x00, 0x00, 0x30, 0xfc, 0xf9, 0x40, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x80, 0x00, + 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x0a, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x33, 0x33, 0x33, 0x00, 0x0c, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x31, 0x88, 0x00, 0x07, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf0, 0xde, 0x9a, 0xf8, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0f, 0x90, 0xb2, 0x83, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf7, 0x21, 0x8c, 0xd5, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0c, 0x6f, 0x39, 0x95, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 13 */ + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x53, 0x44, 0x00, 0x00, 0x53, 0x44, 0x00, 0x01, 0x9a, 0x00, 0x00, 0x01, 0x9a, 0x00, 0x00, + 0x00, 0x00, 0x05, 0x46, 0x00, 0x00, 0x05, 0x46, 0x00, 0x00, 0x00, 0x15, 0x00, 0x00, 0x00, 0x19, + 0x00, 0x00, 0x02, 0x58, 0x00, 0x00, 0x02, 0x58, 0x00, 0x00, 0x00, 0x12, 0x00, 0x00, 0x00, 0x03, + 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x96, 0x00, 0x00, 0x01, 0x2c, 0x00, 0x00, 0x00, 0x96, + 0x00, 0xcf, 0x50, 0xa4, 0x00, 0xcf, 0x50, 0xa4, 0x01, 0x35, 0xd0, 0xa4, 0x01, 0x35, 0xd0, 0xa4, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, + 0x00, 0x0c, 0x80, 0x00, 0x00, 0x0c, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x00, + 0x00, 0x0c, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 14 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x01, 0x7b, 0xab, 0x50, 0x01, 0x2d, 0xb6, 0x48, 0x00, 0x00, 0x16, 0xac, 0x00, 0x22, 0x82, 0x60, + 0x00, 0x00, 0x11, 0x8b, 0x04, 0x4c, 0xcc, 0xb0, 0x00, 0x00, 0x00, 0x14, 0x00, 0x00, 0x16, 0x81, + 0x02, 0x78, 0xfe, 0xe0, 0x03, 0x94, 0x3a, 0xb0, 0x00, 0x10, 0xb4, 0x90, 0x00, 0x00, 0x03, 0x2a, + 0x00, 0x00, 0x25, 0xf6, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x10, 0x00, + 0x08, 0x52, 0xdf, 0x89, 0x05, 0x8c, 0x95, 0x06, 0x01, 0x63, 0x25, 0x41, 0x60, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x7b, 0x47, 0x69, 0x02, 0xe5, 0xdb, 0xae, 0x06, 0xf1, 0x85, 0x78, 0x07, 0xdf, 0xab, 0x88, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 15 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xfe, 0x4c, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x08, 0x66, 0x66, 0x66, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x99, 0x99, 0x9a, 0x00, 0x66, 0x66, 0x66, + 0x00, 0x00, 0x01, 0xf4, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x1e, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x66, 0x66, 0x66, 0x00, 0x04, 0xd4, 0x5e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, 0x28, 0x00, 0x00, 0x00, 0x1e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x66, 0x66, 0x66, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x96, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0xf8, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 16 */ + 0xd8, 0xdc, 0xb8, 0xb0, 0xb4, 0xf3, 0xaa, 0xf8, 0xf9, 0xd1, 0xd9, 0x88, 0x9a, 0xf8, 0xf7, 0x3e, + 0xd8, 0xf3, 0x8a, 0x9a, 0xa7, 0x31, 0xd1, 0xd9, 0xf4, 0x10, 0x36, 0xd8, 0xf3, 0x9f, 0x39, 0xf9, + 0xd1, 0xd9, 0xf4, 0x10, 0x36, 0xd8, 0xf3, 0x8f, 0x9f, 0x08, 0x97, 0x60, 0x8a, 0x21, 0xd1, 0xd9, + 0xf4, 0x10, 0x36, 0xda, 0xf1, 0xff, 0xd8, 0xf1, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xba, 0xb2, + 0xb6, 0xa0, 0x80, 0x90, 0x32, 0x18, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xb8, 0xb0, 0xb4, 0xa4, + 0xdf, 0xa5, 0xde, 0xf3, 0xa8, 0xde, 0xd0, 0xdf, 0xa4, 0x84, 0x9f, 0x24, 0xf2, 0xa9, 0xf8, 0xf9, + 0xd1, 0xda, 0xde, 0xa8, 0xde, 0xdf, 0xdf, 0xdf, 0xd8, 0xf4, 0xb1, 0x8d, 0xf3, 0xa8, 0xd0, 0xb0, + 0xb4, 0x8f, 0xf4, 0xb9, 0xaf, 0xd0, 0xc7, 0xbe, 0xbe, 0xb8, 0xae, 0xd0, 0xf3, 0x9f, 0x75, 0xb2, + 0x86, 0xf4, 0xbe, 0xbe, 0xb9, 0xaf, 0xd0, 0xc3, 0xf1, 0xbe, 0xb8, 0xb0, 0xa3, 0xde, 0xdf, 0xdf, + 0xdf, 0xf2, 0xa3, 0x81, 0xc0, 0x80, 0xcd, 0xc7, 0xcf, 0xbc, 0xbd, 0xb4, 0xa3, 0x88, 0x93, 0xf1, + 0x62, 0x6e, 0x76, 0x7e, 0x88, 0x93, 0xbe, 0xa2, 0x42, 0xa0, 0x4e, 0x56, 0x5e, 0xbe, 0xb9, 0xac, + 0x8d, 0x20, 0xb8, 0xbe, 0xbe, 0xbc, 0xa2, 0x86, 0x9d, 0x08, 0xfd, 0x0f, 0xbc, 0xbc, 0xbc, 0xa3, + 0x82, 0x93, 0x01, 0xa9, 0x83, 0x9e, 0x0e, 0x16, 0x1e, 0xbe, 0xbe, 0xbe, 0xbc, 0xa5, 0x8b, 0x99, + 0x2c, 0x54, 0x7c, 0xbc, 0xbc, 0x85, 0x93, 0xba, 0xa5, 0x2d, 0x55, 0x7d, 0xb8, 0xa5, 0x9d, 0x2c, + 0xfd, 0x36, 0x4c, 0xfd, 0x36, 0x6c, 0xfd, 0x36, 0xf5, 0xa5, 0x85, 0x9f, 0x34, 0x54, 0x74, 0xbd, + 0xbd, 0xbd, 0xb1, 0xb6, 0xba, 0x83, 0x95, 0xa5, 0xf1, 0x0e, 0x16, 0x1e, 0xb2, 0xa7, 0x85, 0x95, + /* bank # 17 */ + 0x2a, 0xf0, 0x50, 0x78, 0x87, 0x93, 0xf1, 0x01, 0xda, 0xa5, 0xdf, 0xdf, 0xdf, 0xd8, 0xa4, 0xdf, + 0xdf, 0xdf, 0xb0, 0x80, 0xf2, 0xa4, 0xc3, 0xcb, 0xc5, 0xf1, 0xb1, 0x8e, 0x94, 0xa4, 0x0e, 0x16, + 0x1e, 0xb2, 0x86, 0xbe, 0xa0, 0x2c, 0x34, 0x3c, 0xbd, 0xbd, 0xb4, 0x96, 0xb8, 0xa1, 0x2c, 0x34, + 0x3c, 0xbd, 0xbd, 0xb6, 0x94, 0xbe, 0xa6, 0x2c, 0xfd, 0x35, 0x34, 0xfd, 0x35, 0x3c, 0xfd, 0x35, + 0xbc, 0xb2, 0x8e, 0x94, 0xb8, 0xbe, 0xbe, 0xa6, 0x2d, 0x55, 0x7d, 0xba, 0xa4, 0x2d, 0x55, 0x7d, + 0xb8, 0xb0, 0xb4, 0xa6, 0x8f, 0x96, 0x2e, 0x36, 0x3e, 0xbc, 0xbc, 0xbc, 0xbd, 0xa6, 0x86, 0x9f, + 0xf5, 0x34, 0x54, 0x74, 0xbc, 0xbe, 0xf1, 0x90, 0xfc, 0xc3, 0x00, 0xd9, 0xf4, 0x11, 0xd4, 0xd8, + 0xf3, 0xa0, 0xdf, 0xf1, 0xbc, 0x86, 0x91, 0xa9, 0x2d, 0x55, 0x7d, 0xbc, 0xbc, 0xbc, 0xa9, 0x80, + 0x90, 0xfc, 0x51, 0x00, 0x10, 0xfc, 0x51, 0x00, 0x10, 0xfc, 0x51, 0x00, 0x10, 0xfc, 0xc1, 0x04, + 0xd9, 0xf2, 0xa0, 0xdf, 0xf4, 0x11, 0xd4, 0xd8, 0xf6, 0xa0, 0xfa, 0x80, 0x90, 0x38, 0xf3, 0xde, + 0xda, 0xf8, 0xf4, 0x11, 0xd4, 0xd8, 0xf1, 0xbd, 0x95, 0xfc, 0xc1, 0x04, 0xd9, 0xbd, 0xbd, 0xbd, + 0xf4, 0x11, 0xd4, 0xd8, 0xf6, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xbe, 0xb5, 0xa7, 0x84, + 0x92, 0x1a, 0xf8, 0xf9, 0xd1, 0xdb, 0x84, 0x93, 0xf7, 0x6a, 0xb6, 0x87, 0x96, 0xf3, 0x09, 0xff, + 0xda, 0xbc, 0xbd, 0xbe, 0xd8, 0xf1, 0xbc, 0xbc, 0xbc, 0xf6, 0xb0, 0x82, 0xb4, 0x97, 0xb8, 0xa9, + 0x02, 0xf7, 0x02, 0xf1, 0xbc, 0x89, 0x99, 0xa7, 0x04, 0xfd, 0x37, 0xa8, 0xdf, 0x87, 0x98, 0xa7, + 0xfc, 0x3d, 0x00, 0x50, 0xf8, 0xf9, 0xd1, 0xd9, 0xa8, 0xdf, 0xf9, 0xd8, 0xf6, 0xbc, 0xbc, 0xbc, + /* bank # 18 */ + 0xbd, 0xbd, 0xbd, 0xbe, 0xbe, 0xbe, 0xb7, 0xa7, 0x81, 0x9a, 0x0b, 0xb4, 0x87, 0x9f, 0x1a, 0xf8, + 0xf9, 0xd1, 0xbb, 0x81, 0xaa, 0xc1, 0xd9, 0xf4, 0x12, 0x3c, 0xd8, 0xf6, 0xb8, 0xa7, 0x1a, 0xf9, + 0xd9, 0xf4, 0x12, 0x3c, 0xd8, 0x8a, 0xf3, 0xbb, 0xaa, 0xc0, 0xc3, 0xb3, 0xaa, 0x8a, 0x9d, 0x1a, + 0xfd, 0x1e, 0xb7, 0x9a, 0x08, 0xb8, 0xb0, 0xb4, 0xa5, 0x85, 0x9d, 0x00, 0xd8, 0xf3, 0xb9, 0xb2, + 0xa9, 0x80, 0xcd, 0xf2, 0xc4, 0xc5, 0xba, 0xf3, 0xa0, 0xd0, 0xde, 0xb1, 0xb4, 0xf7, 0xa7, 0x89, + 0x91, 0x72, 0x89, 0x91, 0x47, 0xb6, 0x97, 0x4a, 0xb9, 0xf2, 0xa9, 0xd0, 0xfa, 0xf9, 0xd1, 0xd9, + 0xf4, 0x12, 0x6a, 0xd8, 0xf3, 0xba, 0xa7, 0xf9, 0xdb, 0xfb, 0xd9, 0xf1, 0xb9, 0xb0, 0x81, 0xa9, + 0xc3, 0xf2, 0xc5, 0xf3, 0xba, 0xa0, 0xd0, 0xf8, 0xd8, 0xf1, 0xb1, 0x89, 0xa7, 0xdf, 0xdf, 0xdf, + 0xf2, 0xa7, 0xc3, 0xcb, 0xc5, 0xf1, 0xb2, 0x87, 0xb8, 0xbe, 0xbe, 0xbe, 0xab, 0xc2, 0xc5, 0xc7, + 0xbe, 0xb5, 0xb9, 0x97, 0xa5, 0x22, 0xf0, 0x48, 0x70, 0x3c, 0x98, 0x40, 0x68, 0x34, 0x58, 0x99, + 0x60, 0xf1, 0xbc, 0xb3, 0x8e, 0x95, 0xaa, 0x25, 0x4d, 0x75, 0xbc, 0xbc, 0xbc, 0xb8, 0xb0, 0xb4, + 0xa7, 0x88, 0x9f, 0xf7, 0x5a, 0xf9, 0xda, 0xf3, 0xa8, 0xf8, 0x88, 0x9d, 0xd0, 0x7c, 0xd8, 0xf7, + 0xa7, 0x88, 0x9f, 0x52, 0xf9, 0xda, 0xf3, 0xa8, 0x88, 0x9c, 0xd0, 0xdf, 0x60, 0x68, 0x70, 0x78, + 0x9d, 0x60, 0x68, 0x70, 0x78, 0x9e, 0x70, 0x78, 0x9f, 0x70, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, 0x42, + 0xf9, 0xba, 0xa0, 0xd0, 0xf3, 0xd9, 0xde, 0xd8, 0xf8, 0xf9, 0xd1, 0xb8, 0xda, 0xa8, 0x88, 0x9e, + 0xd0, 0x64, 0x68, 0x9f, 0x60, 0xd8, 0xa8, 0x84, 0x98, 0xd0, 0xf7, 0x7e, 0xf1, 0xb2, 0xb6, 0xba, + /* bank # 19 */ + 0x85, 0x91, 0xa7, 0xf4, 0x75, 0x9d, 0xf4, 0x75, 0xb5, 0xf1, 0x84, 0x91, 0xa7, 0xf4, 0x75, 0x9d, + 0xf0, 0xa2, 0x87, 0x0d, 0x20, 0x59, 0x70, 0x15, 0x38, 0x40, 0x69, 0xa4, 0xf1, 0x62, 0xf0, 0x19, + 0x31, 0x48, 0xb8, 0xb1, 0xb4, 0xf1, 0xa6, 0x80, 0xc6, 0xf4, 0xb0, 0x81, 0xf3, 0xa7, 0xc6, 0xb1, + 0x8f, 0x97, 0xf7, 0x02, 0xf9, 0xda, 0xf4, 0x13, 0x74, 0xd8, 0xb0, 0xf7, 0xa7, 0x88, 0x9f, 0x52, + 0xf9, 0xd9, 0xf4, 0x13, 0x6d, 0xd8, 0xf1, 0xb2, 0xb6, 0xa6, 0x82, 0x92, 0x2a, 0xf0, 0x50, 0xfd, + 0x08, 0xf1, 0xa7, 0x84, 0x94, 0x02, 0xfd, 0x08, 0xb0, 0xb4, 0x86, 0x97, 0x00, 0xb1, 0xba, 0xa7, + 0x81, 0x61, 0xd9, 0xf4, 0x13, 0x8c, 0xd8, 0xf1, 0x41, 0xda, 0xf4, 0x13, 0x8c, 0xd8, 0xf1, 0xb8, + 0xb2, 0xa6, 0x82, 0xc0, 0xd8, 0xf1, 0xb0, 0xb6, 0x86, 0x92, 0xa7, 0x16, 0xfd, 0x04, 0x0f, 0xfd, + 0x04, 0xba, 0x87, 0x91, 0xa7, 0xf4, 0x75, 0xab, 0xb2, 0xf4, 0x75, 0xb5, 0xd8, 0xf1, 0xbe, 0xbe, + 0xbe, 0xbd, 0xbd, 0xbd, 0xb2, 0xba, 0x84, 0xa7, 0xc3, 0xc5, 0xc7, 0xb2, 0xbc, 0xbc, 0xbc, 0xb6, + 0x87, 0x91, 0xaf, 0xf4, 0x75, 0x9d, 0xa0, 0x8f, 0xf1, 0x0b, 0xf0, 0x20, 0x59, 0x70, 0x15, 0x38, + 0x40, 0x69, 0x64, 0x19, 0x31, 0x48, 0xf1, 0x80, 0x90, 0xaf, 0x6e, 0xfd, 0x04, 0x67, 0xfd, 0x04, + 0x8f, 0x91, 0xa7, 0xf4, 0x75, 0xab, 0xf4, 0x75, 0xb5, 0xf1, 0xbe, 0xbc, 0xbd, 0xf7, 0xbe, 0xb0, + 0xb4, 0xba, 0x88, 0x9e, 0xa3, 0x6a, 0x9f, 0x66, 0xf0, 0xb1, 0xb5, 0xb9, 0x8a, 0x9a, 0xa2, 0x2c, + 0x50, 0x78, 0xb2, 0xb9, 0x8a, 0xaf, 0xc0, 0xc3, 0xc5, 0xc7, 0x89, 0xad, 0xd0, 0xc4, 0xc7, 0x83, + 0xa1, 0xc2, 0xc5, 0xba, 0xbc, 0xbc, 0xbc, 0xb2, 0x81, 0xa2, 0xc0, 0xc3, 0xc5, 0xc7, 0xbc, 0xbc, + /* bank # 20 */ + 0xbd, 0xf4, 0x74, 0x91, 0xf3, 0xba, 0xa3, 0xfa, 0xf9, 0xd1, 0xd9, 0xf4, 0x14, 0x28, 0xd8, 0x74, + 0xa2, 0xbe, 0xbe, 0xbe, 0xba, 0xb1, 0x82, 0xa3, 0xd0, 0xc7, 0xa9, 0xd0, 0x8d, 0xc4, 0xc7, 0xa3, + 0x81, 0xc1, 0xc3, 0xf3, 0xa6, 0x8d, 0xc2, 0xbe, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xba, 0xb1, 0xaa, + 0x8f, 0xc0, 0xc3, 0xc5, 0xc7, 0xbe, 0xbc, 0xbc, 0xbc, 0xb2, 0xb9, 0x88, 0xaf, 0xc0, 0xc3, 0xc5, + 0xc7, 0x80, 0xad, 0xd0, 0xc0, 0xc3, 0x89, 0xa1, 0xc0, 0xc3, 0xba, 0x81, 0xa2, 0xc0, 0xc3, 0xc5, + 0xc7, 0xbc, 0xf4, 0x74, 0x91, 0xf3, 0xba, 0xa3, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x14, 0x79, 0xd8, + 0x74, 0xa2, 0xbe, 0xbe, 0xbe, 0xb8, 0xb1, 0x82, 0xa7, 0xd0, 0xc7, 0xba, 0xa0, 0x8d, 0xc4, 0xc7, + 0xa9, 0x81, 0xc0, 0xc3, 0xf3, 0xa5, 0x8d, 0xc2, 0xbe, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xba, 0xb1, + 0xa8, 0x8f, 0xc0, 0xc3, 0xc5, 0xc7, 0xbe, 0xf3, 0xba, 0xb2, 0xb6, 0xa3, 0x83, 0x93, 0x08, 0xf9, + 0xd9, 0xf4, 0x14, 0xf7, 0xd8, 0xf0, 0xb8, 0xb0, 0xa3, 0x85, 0x94, 0x04, 0x28, 0x50, 0x78, 0xf1, + 0xb4, 0x84, 0x93, 0x69, 0xd9, 0xb6, 0xa5, 0x8d, 0x94, 0x20, 0x2c, 0x34, 0x3c, 0xb4, 0xa4, 0xde, + 0xdf, 0xf8, 0xf4, 0x14, 0xc1, 0xd8, 0xf1, 0xa4, 0xf8, 0xa3, 0x84, 0x94, 0x41, 0xd9, 0xa4, 0xdf, + 0xf8, 0xd8, 0xf1, 0x94, 0xfc, 0xc1, 0x04, 0xd9, 0xa4, 0xfb, 0xa3, 0x86, 0xc0, 0xb1, 0x82, 0x9e, + 0x06, 0xfd, 0x1e, 0xa6, 0x81, 0x96, 0x42, 0x93, 0xf0, 0x68, 0xb0, 0xa3, 0xf1, 0x83, 0x96, 0x01, + 0xf5, 0x83, 0x93, 0x00, 0xa6, 0x86, 0x96, 0xf0, 0x34, 0x83, 0x18, 0xf1, 0xa1, 0x8d, 0x68, 0xa3, + 0x81, 0x9b, 0xdb, 0x19, 0x8b, 0xa1, 0xc6, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, + /* bank # 21 */ + 0xbd, 0xbd, 0xd8, 0xf7, 0xb8, 0xb4, 0xb0, 0xa7, 0x9d, 0x88, 0x72, 0xf9, 0xbc, 0xbd, 0xbe, 0xd9, + 0xf4, 0x17, 0x96, 0xd8, 0xf2, 0xb8, 0xad, 0xf8, 0xf9, 0xd1, 0xda, 0xde, 0xba, 0xa1, 0xde, 0xae, + 0xde, 0xf8, 0xd8, 0xb2, 0x81, 0xbe, 0xbe, 0xb9, 0xaf, 0xd0, 0xc1, 0xbc, 0xbc, 0xbd, 0xbd, 0xb1, + 0xb4, 0xf1, 0xac, 0x8c, 0x92, 0x0a, 0x18, 0xb5, 0xaf, 0x8c, 0x9d, 0x41, 0xdb, 0x9c, 0x11, 0x8e, + 0xad, 0xc0, 0xbe, 0xbe, 0xba, 0xae, 0xc3, 0xc5, 0xc7, 0x8d, 0xa8, 0xc6, 0xc7, 0xc7, 0xc7, 0xa6, + 0xde, 0xdf, 0xdf, 0xdf, 0xa5, 0xd0, 0xde, 0xdf, 0xbe, 0xbe, 0xd8, 0xb9, 0xac, 0xdf, 0xaf, 0x8d, + 0x9c, 0x11, 0xd9, 0x8c, 0xc5, 0xda, 0xc1, 0xd8, 0xaf, 0x8f, 0x21, 0xf5, 0x9f, 0x00, 0xf1, 0x8c, + 0x9c, 0x45, 0xd9, 0x8f, 0xac, 0xc1, 0xd8, 0xf2, 0xaf, 0xdf, 0xf8, 0xf8, 0xdf, 0xf8, 0xf8, 0xf8, + 0xaf, 0x8f, 0x9f, 0x59, 0xd1, 0xdb, 0xf1, 0x8c, 0x9c, 0x31, 0xf2, 0x8f, 0xaf, 0xd0, 0xc3, 0xd8, + 0xaf, 0x8f, 0x9f, 0x39, 0xd1, 0xdb, 0xf1, 0x8c, 0x9c, 0x69, 0xf2, 0x8f, 0xaf, 0xd0, 0xc5, 0xd8, + 0x8f, 0xbe, 0xbe, 0xba, 0xa1, 0xc6, 0xbc, 0xbc, 0xbd, 0xbd, 0xf2, 0xb1, 0xb5, 0xb9, 0xae, 0xf9, + 0xda, 0xf4, 0x17, 0x69, 0xd8, 0xf2, 0x8e, 0xc2, 0xf1, 0xb2, 0x80, 0x9a, 0xf5, 0xaf, 0x24, 0xd9, + 0xf4, 0x17, 0x69, 0xd8, 0xf5, 0x44, 0xd9, 0xf4, 0x17, 0x69, 0xd8, 0xf5, 0x64, 0xd9, 0xf4, 0x17, + 0x69, 0xd8, 0xf1, 0xb1, 0xb6, 0x8b, 0x90, 0xaf, 0x2d, 0x55, 0x7d, 0xb5, 0x8c, 0x9f, 0xad, 0x0e, + 0x16, 0x1e, 0x8b, 0x9d, 0xab, 0x2c, 0x54, 0x7c, 0x8d, 0x9f, 0xaa, 0x2e, 0x56, 0x7e, 0x8a, 0x9c, + 0xaa, 0x2c, 0x54, 0x7c, 0x9b, 0xac, 0x26, 0x46, 0x66, 0xaf, 0x8d, 0x9d, 0x00, 0x9c, 0x0d, 0xdb, + /* bank # 22 */ + 0x11, 0x8f, 0x19, 0xf4, 0x16, 0x09, 0xd8, 0x17, 0x69, 0xd8, 0xf1, 0xb2, 0x81, 0xb6, 0x90, 0xaf, + 0x2d, 0x55, 0x7d, 0xb1, 0x8f, 0xb5, 0x9f, 0xaf, 0xf5, 0x2c, 0x54, 0x7c, 0xf1, 0xb2, 0x8c, 0x9f, + 0xad, 0x6d, 0xdb, 0x71, 0x79, 0xf4, 0x16, 0x37, 0xd8, 0xf3, 0xba, 0xa1, 0xde, 0xf8, 0xf1, 0x80, + 0xa1, 0xc3, 0xc5, 0xc7, 0xf4, 0x16, 0x46, 0xd8, 0xf3, 0xb6, 0xba, 0x91, 0xfc, 0xc0, 0x28, 0xda, + 0xa1, 0xf8, 0xd9, 0xf4, 0x17, 0x69, 0xd8, 0xf3, 0xb9, 0xae, 0xf8, 0xf9, 0xd1, 0xd9, 0xf8, 0xf4, + 0x17, 0x69, 0xd8, 0xf1, 0xba, 0xb1, 0xb5, 0xa0, 0x8b, 0x93, 0x3e, 0x5e, 0x7e, 0xab, 0x83, 0xc0, + 0xc5, 0xb2, 0xb6, 0xa3, 0x87, 0xc0, 0xc3, 0xc5, 0xc7, 0xa2, 0x88, 0xc0, 0xc3, 0xc5, 0xc7, 0xa4, + 0x86, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, 0x85, 0xc4, 0xc7, 0xac, 0x8d, 0xc0, 0xbe, 0xbe, 0xbc, 0xbc, + 0xbd, 0xbd, 0xb9, 0xb1, 0xb5, 0xad, 0xd0, 0xde, 0xaf, 0x8c, 0x9c, 0x41, 0xd9, 0xf4, 0x16, 0xb5, + 0xd8, 0xf1, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x16, 0xce, 0xd8, 0xf1, 0xaf, 0x8d, 0x9c, 0x31, 0xda, + 0x8c, 0xc5, 0xd9, 0xc3, 0xd8, 0xaf, 0x8f, 0x21, 0xf5, 0x9f, 0x00, 0xf1, 0xad, 0xd0, 0xb0, 0x82, + 0x9f, 0x02, 0xf4, 0x16, 0xce, 0xd8, 0xf1, 0xaf, 0x8d, 0x9c, 0x31, 0xd9, 0x8c, 0xc5, 0xda, 0xc3, + 0xd8, 0xaf, 0x8f, 0x21, 0xf5, 0x9f, 0x00, 0xf1, 0xad, 0xd0, 0xb0, 0x83, 0x9f, 0x02, 0xd8, 0xf1, + 0xb1, 0x8c, 0xad, 0xc1, 0xbe, 0xbe, 0xbd, 0xbd, 0xba, 0xb6, 0xac, 0x8d, 0x9c, 0x40, 0xbc, 0xbc, + 0xb2, 0xa0, 0xde, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xfd, 0x0f, 0xf5, 0xaf, 0x88, 0x98, 0x00, 0x2c, + 0x54, 0x7c, 0xf1, 0xaf, 0x80, 0x9f, 0x01, 0xdb, 0x09, 0x11, 0x19, 0xf4, 0x17, 0x08, 0xd8, 0xf2, + /* bank # 23 */ + 0xa1, 0xf8, 0xf9, 0xd1, 0xda, 0xf1, 0xac, 0xde, 0xd8, 0xf3, 0xae, 0xde, 0xf8, 0xf4, 0x1a, 0x83, + 0xd8, 0xf1, 0xa7, 0x83, 0xc0, 0xc3, 0xc5, 0xc7, 0xa8, 0x82, 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x84, + 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, 0x85, 0xd0, 0xc0, 0xc3, 0x8d, 0x9d, 0xaf, 0x39, 0xd9, 0xf4, 0x17, + 0x69, 0xd8, 0xf1, 0x83, 0xb5, 0x9e, 0xae, 0x34, 0xfd, 0x0a, 0x54, 0xfd, 0x0a, 0x74, 0xfd, 0x0a, + 0xf2, 0xa1, 0xde, 0xf8, 0xf8, 0xf8, 0xf1, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xb9, 0xb1, 0xb5, + 0x8c, 0xad, 0xc0, 0xaf, 0x9c, 0x11, 0xd9, 0xae, 0xc0, 0xbc, 0xbc, 0xb2, 0x8e, 0xc3, 0xc5, 0xc7, + 0xbc, 0xbc, 0xd8, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xd8, 0xf2, 0xba, 0xb2, 0xb5, 0xaf, 0x81, + 0x97, 0x01, 0xd1, 0xb9, 0xa7, 0xc0, 0xda, 0xf4, 0x17, 0x81, 0xd8, 0xf2, 0xba, 0xae, 0xf8, 0xf9, + 0xd1, 0xda, 0xf3, 0xbe, 0xbe, 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xb8, 0xb0, 0xb4, 0xa5, + 0x85, 0x9c, 0x08, 0xbe, 0xbc, 0xbd, 0xd8, 0xf7, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbb, 0xb4, + 0xb0, 0xaf, 0x9e, 0x88, 0x62, 0xf9, 0xbc, 0xbd, 0xd9, 0xf4, 0x19, 0xdc, 0xd8, 0xf1, 0xbc, 0xbc, + 0xbc, 0xb1, 0x85, 0xba, 0xb5, 0xa0, 0x98, 0x06, 0x26, 0x46, 0xbc, 0xb9, 0xb3, 0xb6, 0xf1, 0xaf, + 0x81, 0x90, 0x2d, 0x55, 0x7d, 0xb1, 0xb5, 0xaf, 0x8f, 0x9f, 0xf5, 0x2c, 0x54, 0x7c, 0xf1, 0xbb, + 0xaf, 0x86, 0x9f, 0x69, 0xdb, 0x71, 0x79, 0xda, 0xf3, 0xa0, 0xdf, 0xf8, 0xf1, 0xa1, 0xde, 0xf2, + 0xf8, 0xd8, 0xb3, 0xb7, 0xf1, 0x8c, 0x9b, 0xaf, 0x19, 0xd9, 0xac, 0xde, 0xf3, 0xa0, 0xdf, 0xf8, + 0xd8, 0xaf, 0x80, 0x90, 0x69, 0xd9, 0xa0, 0xfa, 0xf1, 0xb2, 0x80, 0xa1, 0xc3, 0xc5, 0xc7, 0xf2, + /* bank # 24 */ + 0xa0, 0xd0, 0xdf, 0xf8, 0xf4, 0x19, 0xc6, 0xd8, 0xf2, 0xa0, 0xd0, 0xdf, 0xf1, 0xbc, 0xbc, 0xbc, + 0xb1, 0xad, 0x8a, 0x9e, 0x26, 0x46, 0x66, 0xbc, 0xb3, 0xf3, 0xa2, 0xde, 0xf8, 0xf4, 0x1a, 0x0c, + 0xd8, 0xf1, 0xaa, 0x8d, 0xc1, 0xf2, 0xa1, 0xf8, 0xf9, 0xd1, 0xda, 0xf4, 0x18, 0x51, 0xd8, 0xf1, + 0xaf, 0x8a, 0x9a, 0x21, 0x8f, 0x90, 0xf5, 0x10, 0xda, 0xf4, 0x18, 0x51, 0xd8, 0xf1, 0x91, 0xfc, + 0xc0, 0x04, 0xd9, 0xf4, 0x18, 0x98, 0xd8, 0xf3, 0xa1, 0xde, 0xf8, 0xa0, 0xdf, 0xf8, 0xf4, 0x19, + 0xc6, 0xf3, 0x91, 0xfc, 0xc0, 0x07, 0xd9, 0xf4, 0x18, 0x98, 0xd8, 0xf1, 0xaf, 0xb1, 0x84, 0x9c, + 0x01, 0xb3, 0xb5, 0x80, 0x97, 0xdb, 0xf3, 0x21, 0xb9, 0xa7, 0xd9, 0xf8, 0xf4, 0x18, 0x98, 0xd8, + 0xf3, 0xb9, 0xa7, 0xde, 0xf8, 0xbb, 0xf1, 0xa3, 0x87, 0xc0, 0xc3, 0xc5, 0xc7, 0xa4, 0x88, 0xc0, + 0xc3, 0xc5, 0xc7, 0xa5, 0x89, 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x86, 0xc4, 0xc7, 0xa1, 0x82, 0xc3, + 0xc5, 0xc7, 0xf3, 0xa1, 0xde, 0xf4, 0x19, 0xdc, 0xd8, 0xf1, 0xbb, 0xb3, 0xb7, 0xa1, 0xf8, 0xf9, + 0xd1, 0xda, 0xf2, 0xa0, 0xd0, 0xdf, 0xf8, 0xd8, 0xf1, 0xb9, 0xb1, 0xb6, 0xa8, 0x87, 0x90, 0x2d, + 0x55, 0x7d, 0xf5, 0xb5, 0xa8, 0x88, 0x98, 0x2c, 0x54, 0x7c, 0xf1, 0xaf, 0x86, 0x98, 0x29, 0xdb, + 0x31, 0x39, 0xf4, 0x19, 0xdc, 0xd8, 0xf1, 0xb3, 0xb6, 0xa7, 0x8a, 0x90, 0x4c, 0x54, 0x5c, 0xba, + 0xa0, 0x81, 0x90, 0x2d, 0x55, 0x7d, 0xbb, 0xf2, 0xa2, 0xf8, 0xf9, 0xd1, 0xda, 0xde, 0xf4, 0x19, + 0xdc, 0xd8, 0xf1, 0xba, 0xb0, 0xab, 0x8f, 0xc0, 0xc7, 0xb3, 0xa3, 0x83, 0xc0, 0xc3, 0xc5, 0xc7, + 0xa2, 0x84, 0xc0, 0xc3, 0xc5, 0xc7, 0xa4, 0x85, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, 0x86, 0xc0, 0xc3, + /* bank # 25 */ + 0xac, 0x8c, 0xc2, 0xf3, 0xae, 0xde, 0xf8, 0xf8, 0xf4, 0x1a, 0x83, 0xd8, 0xf1, 0xb2, 0xbb, 0xa3, + 0x83, 0xc0, 0xc3, 0xc5, 0xc7, 0xa4, 0x82, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, 0x84, 0xc0, 0xc3, 0xc5, + 0xc7, 0xa6, 0x85, 0xc0, 0xc3, 0xac, 0x8c, 0xc4, 0xb3, 0xb7, 0xaf, 0x85, 0x95, 0x56, 0xfd, 0x0f, + 0x86, 0x96, 0x06, 0xfd, 0x0f, 0xf0, 0x84, 0x9f, 0xaf, 0x4c, 0x70, 0xfd, 0x0f, 0xf1, 0x86, 0x96, + 0x2e, 0xfd, 0x0f, 0x84, 0x9f, 0x72, 0xfd, 0x0f, 0xdf, 0xaf, 0x2c, 0x54, 0x7c, 0xaf, 0x8c, 0x69, + 0xdb, 0x71, 0x79, 0x8b, 0x9c, 0x61, 0xf4, 0x19, 0x5c, 0xda, 0x19, 0xdc, 0xd8, 0xf1, 0xab, 0x83, + 0x91, 0x28, 0xfd, 0x05, 0x54, 0xfd, 0x05, 0x7c, 0xfd, 0x05, 0xb8, 0xbd, 0xbd, 0xbd, 0xb5, 0xa3, + 0x8b, 0x95, 0x05, 0x2d, 0x55, 0xbd, 0xb4, 0xbb, 0xad, 0x8e, 0x93, 0x0e, 0x16, 0x1e, 0xb7, 0xf3, + 0xa2, 0xde, 0xf8, 0xf8, 0xf4, 0x1a, 0x0c, 0xd8, 0xf2, 0xa1, 0xf8, 0xf9, 0xd1, 0xd9, 0xf1, 0xaf, + 0x8d, 0x9a, 0x01, 0xf5, 0x8f, 0x90, 0xdb, 0x00, 0xf4, 0x19, 0xdc, 0xda, 0xf1, 0xaa, 0x8d, 0xc0, + 0xae, 0x8b, 0xc1, 0xc3, 0xc5, 0xa1, 0xde, 0xa7, 0x83, 0xc0, 0xc3, 0xc5, 0xc7, 0xa8, 0x84, 0xc0, + 0xc3, 0xc5, 0xc7, 0xa9, 0x85, 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x86, 0xd0, 0xc0, 0xc3, 0xa2, 0x81, + 0xc3, 0xc5, 0xc7, 0xf4, 0x19, 0xdc, 0xf1, 0xbb, 0xb3, 0xa3, 0xde, 0xdf, 0xdf, 0xdf, 0xa4, 0x8c, + 0xc4, 0xc5, 0xc5, 0xc5, 0xa5, 0xde, 0xdf, 0xdf, 0xdf, 0xa6, 0xde, 0xdf, 0xd8, 0xf3, 0xb9, 0xae, + 0xdf, 0xba, 0xae, 0xde, 0xbb, 0xa2, 0xde, 0xbe, 0xbc, 0xb3, 0xbd, 0xb7, 0xaf, 0x8e, 0x9c, 0x01, + 0xd1, 0xac, 0xc0, 0xd9, 0xae, 0xde, 0xd8, 0xf1, 0xb1, 0x83, 0xb9, 0xa7, 0xd0, 0xc4, 0xb8, 0xae, + /* bank # 26 */ + 0xde, 0xbe, 0xbe, 0xbe, 0xbb, 0xbc, 0xbc, 0xbc, 0xb3, 0xbd, 0xbd, 0xbd, 0xd8, 0xf3, 0xa2, 0xf8, + 0xf9, 0xd1, 0xd9, 0xf4, 0x1a, 0x81, 0xd8, 0xf5, 0xad, 0x8d, 0x9d, 0x2c, 0x54, 0x7c, 0xf1, 0xaf, + 0x49, 0xda, 0xc3, 0xc5, 0xd9, 0xc5, 0xc3, 0xd8, 0xaf, 0x9f, 0x69, 0xd0, 0xda, 0xc7, 0xd9, 0x8f, + 0xc3, 0x8d, 0xaf, 0xc7, 0xd8, 0xb9, 0xa9, 0x8f, 0x9f, 0xf0, 0x54, 0x78, 0xf1, 0xfd, 0x0f, 0xa6, + 0xb1, 0x89, 0xc2, 0xb3, 0xaf, 0x8f, 0x9f, 0x2e, 0xfd, 0x11, 0xb1, 0xb5, 0xa9, 0x89, 0x9f, 0x2c, + 0xf3, 0xae, 0xdf, 0xf8, 0xf8, 0xf4, 0x1c, 0x38, 0xd8, 0xf1, 0xad, 0x86, 0x99, 0x06, 0xfd, 0x10, + 0xdf, 0xf8, 0xfd, 0x0f, 0xad, 0x8d, 0x9d, 0x4c, 0xbb, 0xb3, 0xad, 0x8f, 0x9d, 0x2a, 0xfd, 0x0f, + 0xb7, 0x92, 0xfc, 0xc0, 0x04, 0xd9, 0xf4, 0x18, 0x20, 0xd8, 0xfc, 0xc0, 0x08, 0xd9, 0xf4, 0x19, + 0x87, 0xd8, 0xf1, 0xd8, 0xf3, 0xba, 0xb2, 0xb6, 0xae, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x1c, 0x36, + 0xd8, 0xf1, 0xaf, 0xde, 0xf9, 0xfd, 0x0f, 0x80, 0x90, 0x2c, 0x54, 0x7c, 0xa0, 0x2a, 0xf0, 0x50, + 0x78, 0xfd, 0x0f, 0xf1, 0xa2, 0x82, 0x9c, 0x00, 0x24, 0x44, 0x64, 0xa9, 0x8f, 0x94, 0xf0, 0x04, + 0xfd, 0x0f, 0x0c, 0x30, 0xfd, 0x0f, 0x1c, 0x95, 0x20, 0x48, 0xfd, 0x0f, 0xf1, 0x99, 0xc1, 0x2c, + 0x54, 0x7c, 0xaa, 0x82, 0x99, 0x02, 0xfd, 0x0f, 0x2e, 0xfd, 0x0f, 0x56, 0xfd, 0x0f, 0x7e, 0xfd, + 0x0f, 0xac, 0x83, 0x9f, 0xf0, 0x04, 0x28, 0x50, 0x78, 0xfd, 0x0f, 0x8c, 0x90, 0xf1, 0x21, 0xf5, + 0x8c, 0x9c, 0x2c, 0xf1, 0xaf, 0xde, 0xf1, 0x89, 0xaf, 0x9f, 0xfc, 0xc0, 0x00, 0xd9, 0xc1, 0x8a, + 0xc1, 0x82, 0xc1, 0xd8, 0xfc, 0xc0, 0x04, 0xd9, 0xc3, 0x8a, 0xc3, 0x82, 0xc3, 0xd8, 0xfc, 0xc0, + /* bank # 27 */ + 0x08, 0xd9, 0xc5, 0x8a, 0xc5, 0x82, 0xc5, 0xd8, 0xfc, 0xc0, 0x0c, 0xd9, 0xc7, 0x8a, 0xc7, 0x82, + 0xc7, 0xd8, 0xfc, 0xc0, 0x10, 0xd9, 0xf4, 0x1b, 0xf0, 0xd8, 0xf1, 0x8b, 0xab, 0xd0, 0xc0, 0x9f, + 0x2e, 0xfd, 0x0f, 0xa0, 0xde, 0xab, 0xd0, 0x90, 0x65, 0xa0, 0x8f, 0x9f, 0x4a, 0xfd, 0x0f, 0xab, + 0x8b, 0x90, 0x00, 0xb9, 0xa9, 0xc1, 0xf3, 0xae, 0xdf, 0xf8, 0xf4, 0x1c, 0x38, 0xd8, 0xf1, 0xba, + 0xb1, 0xb6, 0x89, 0xab, 0xc1, 0xb2, 0xaf, 0xd0, 0x8b, 0x9f, 0x3e, 0xfd, 0x0f, 0x5a, 0xfd, 0x0f, + 0x9f, 0xfc, 0xc0, 0x00, 0xd9, 0xf1, 0x8f, 0xa2, 0xc6, 0xd8, 0xfc, 0xc0, 0x04, 0xd9, 0x8f, 0xa2, + 0xc7, 0x84, 0xab, 0xd0, 0xc0, 0xaf, 0x8a, 0x9b, 0x1e, 0xfd, 0x0f, 0x36, 0xfd, 0x0f, 0xa4, 0x8f, + 0x30, 0xaa, 0x9a, 0x40, 0xd8, 0x9f, 0xfc, 0xc0, 0x08, 0xd9, 0x8f, 0xa2, 0xd0, 0xc6, 0x84, 0xab, + 0xd0, 0xc2, 0xaf, 0x8a, 0x9b, 0x1e, 0xfd, 0x0f, 0x56, 0xfd, 0x0f, 0xa4, 0x8f, 0x34, 0xaa, 0x9a, + 0x40, 0x84, 0xab, 0xd0, 0xc4, 0xaf, 0x8a, 0x9b, 0x3e, 0xfd, 0x0f, 0x56, 0xfd, 0x0f, 0xa4, 0xd0, + 0x8f, 0x30, 0xaa, 0x9a, 0x4c, 0xd8, 0x9f, 0xfc, 0xc0, 0x0c, 0xd9, 0x8f, 0xa2, 0xd0, 0xc7, 0x84, + 0xab, 0xd0, 0xc6, 0xaf, 0x8a, 0x9b, 0x1e, 0xfd, 0x0f, 0x76, 0xfd, 0x0f, 0xa4, 0xd0, 0x8f, 0x34, + 0xaa, 0x9a, 0x40, 0x85, 0xab, 0xd0, 0xc0, 0xaf, 0x8a, 0x9b, 0x3e, 0xfd, 0x0f, 0x76, 0xfd, 0x0f, + 0xa5, 0x8f, 0x30, 0xaa, 0x9a, 0x4c, 0x85, 0xab, 0xd0, 0xc2, 0xaf, 0x8a, 0x9b, 0x5e, 0xfd, 0x0f, + 0x76, 0xfd, 0x0f, 0xa5, 0x8f, 0x34, 0xaa, 0xd0, 0x9a, 0x50, 0xd8, 0xaf, 0xf8, 0xf4, 0x1a, 0xe6, + 0xf1, 0xd8, 0x8b, 0x9c, 0xaf, 0x2a, 0xfd, 0x0f, 0x8a, 0x9f, 0xb9, 0xaf, 0x02, 0xfd, 0x0f, 0x26, + /* bank # 28 */ + 0xfd, 0x0f, 0x46, 0xfd, 0x0f, 0x66, 0xfd, 0x0f, 0x83, 0xb5, 0x9f, 0xba, 0xa3, 0x00, 0x2c, 0x54, + 0x7c, 0xb6, 0x82, 0x92, 0xa0, 0x31, 0xd9, 0xad, 0xc3, 0xda, 0xad, 0xc5, 0xd8, 0x8d, 0xa0, 0x39, + 0xda, 0x82, 0xad, 0xc7, 0xd8, 0xf3, 0x9e, 0xfc, 0xc0, 0x04, 0xd9, 0xf4, 0x17, 0x10, 0xd8, 0xfc, + 0xc0, 0x08, 0xd9, 0xf4, 0x19, 0x0b, 0xd8, 0xf1, 0xd8, 0xf1, 0xb9, 0xb1, 0xb5, 0xa9, 0xde, 0xf8, + 0x89, 0x99, 0xaf, 0x31, 0xd9, 0xf4, 0x1c, 0x8c, 0xd8, 0xf1, 0x85, 0xaf, 0x29, 0xd9, 0x84, 0xa9, + 0xc2, 0xd8, 0x85, 0xaf, 0x49, 0xd9, 0x84, 0xa9, 0xc4, 0xd8, 0x85, 0xaf, 0x69, 0xd9, 0x84, 0xa9, + 0xc6, 0xd8, 0x89, 0xaf, 0x39, 0xda, 0x8e, 0xa9, 0x50, 0xf4, 0x1c, 0x8c, 0xd8, 0xf1, 0x89, 0xaa, + 0x7c, 0xfd, 0x02, 0x9a, 0x68, 0xd8, 0xf1, 0xaa, 0xfb, 0xda, 0x89, 0x99, 0xaf, 0x26, 0xfd, 0x0f, + 0x8f, 0x95, 0x25, 0x89, 0x9f, 0xa9, 0x12, 0xfd, 0x0f, 0xf4, 0x1c, 0x75, 0xd8, 0xf3, 0x9e, 0xfc, + 0xc1, 0x04, 0xd9, 0xf4, 0x1b, 0x3d, 0xd8, 0xfc, 0xc1, 0x08, 0xd9, 0xf4, 0x1a, 0x58, 0xd8, 0xf1, + 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, 0xf3, 0xb8, 0xb4, 0xb0, 0x8f, 0xa8, 0xc0, 0xf9, 0xac, 0x84, 0x97, + 0xf5, 0x1a, 0xf1, 0xf8, 0xf9, 0xd1, 0xda, 0xa8, 0xde, 0xd8, 0x95, 0xfc, 0xc1, 0x03, 0xd9, 0xa8, + 0xde, 0xd8, 0xbc, 0xbc, 0xf1, 0x98, 0xfc, 0xc0, 0x1c, 0xdb, 0x95, 0xfc, 0xc0, 0x03, 0xa5, 0xde, + 0xa4, 0xde, 0xd8, 0xac, 0x88, 0x95, 0x00, 0xd1, 0xd9, 0xa5, 0xf8, 0xd8, 0xa4, 0xfc, 0x80, 0x04, + 0x88, 0x95, 0xa4, 0xfc, 0x08, 0x04, 0x20, 0xf7, 0xbc, 0xbc, 0xbd, 0xbd, 0xb5, 0xac, 0x84, 0x9f, + 0xf6, 0x02, 0xf8, 0xf9, 0xd1, 0xdb, 0x84, 0x93, 0xf7, 0x6a, 0xf9, 0xd9, 0xf3, 0xbc, 0xbc, 0xa8, + /* bank # 29 */ + 0x88, 0x92, 0x18, 0xbc, 0xbc, 0xd8, 0xbc, 0xbc, 0xb4, 0xa8, 0x88, 0x9e, 0x08, 0xf4, 0xbe, 0xbe, + 0xa1, 0xd0, 0xbc, 0xbc, 0xf7, 0xbe, 0xbe, 0xb5, 0xac, 0x84, 0x93, 0x6a, 0xf9, 0xbd, 0xbd, 0xb4, + 0xd9, 0xf2, 0xac, 0x8c, 0x97, 0x18, 0xf6, 0x84, 0x9c, 0x02, 0xf8, 0xf9, 0xdb, 0xd1, 0xf1, 0xa5, + 0xdf, 0xd8, 0xf7, 0xbe, 0xbe, 0xbd, 0xbd, 0xa7, 0x9d, 0x88, 0x7a, 0xf9, 0xd9, 0xf4, 0x1e, 0xd6, + 0xd8, 0xf1, 0xbe, 0xbe, 0xac, 0xde, 0xdf, 0xac, 0x88, 0x9f, 0xf7, 0x5a, 0x56, 0xf1, 0xbc, 0xbc, + 0xbd, 0xbd, 0x95, 0xfc, 0xc0, 0x07, 0xda, 0xf4, 0x1e, 0x71, 0xd8, 0xf1, 0xfc, 0xc0, 0x00, 0xdb, + 0x9c, 0xfc, 0xc1, 0x00, 0xf4, 0x1e, 0x96, 0xd8, 0xf1, 0xac, 0x95, 0xfc, 0xc0, 0x08, 0xda, 0xf4, + 0x1d, 0xb3, 0xd8, 0xf1, 0x82, 0x90, 0x79, 0x2d, 0x55, 0xf5, 0x8c, 0x9c, 0x04, 0xac, 0x2c, 0x54, + 0xf1, 0xbc, 0xbc, 0xbc, 0x80, 0x5d, 0xdb, 0x49, 0x51, 0xf4, 0xbc, 0x1d, 0x91, 0xda, 0xbc, 0x1e, + 0x6d, 0xd8, 0xf5, 0x86, 0x98, 0x38, 0xd9, 0xf1, 0x82, 0x90, 0x2d, 0xd8, 0xac, 0xd0, 0x86, 0x98, + 0xf5, 0x5c, 0xd9, 0xf1, 0x82, 0x90, 0x55, 0xd8, 0xac, 0x8c, 0x9c, 0x00, 0x00, 0xa5, 0xdf, 0xf8, + 0xf4, 0x1d, 0xbe, 0xd8, 0xf1, 0x82, 0x96, 0x2d, 0x55, 0x7d, 0x8c, 0x9c, 0x34, 0x18, 0xf1, 0xac, + 0x95, 0xf5, 0x1c, 0xd9, 0xf4, 0x1e, 0x6d, 0xd8, 0xf1, 0xac, 0x83, 0x90, 0x45, 0xd9, 0xa0, 0xf8, + 0xac, 0x8c, 0x9c, 0x06, 0xd2, 0xa1, 0x91, 0x00, 0x2c, 0x81, 0xd6, 0xf0, 0xa1, 0xd0, 0x8c, 0x9c, + 0x28, 0xd3, 0x87, 0xd4, 0xa7, 0x8c, 0x20, 0xd3, 0xf1, 0xa4, 0x84, 0x90, 0x2c, 0x54, 0x7c, 0xd8, + 0xac, 0x83, 0x90, 0x45, 0xd9, 0xf4, 0x1e, 0x96, 0xd8, 0xf1, 0xac, 0x81, 0x91, 0x02, 0xfd, 0x14, + /* bank # 30 */ + 0x85, 0x66, 0xfd, 0x1d, 0x88, 0x4e, 0xfd, 0x1b, 0x87, 0xd4, 0xfd, 0x54, 0xad, 0x8d, 0x4e, 0xf0, + 0x81, 0x9c, 0xab, 0xd6, 0xfd, 0x06, 0x8d, 0x31, 0x8c, 0x10, 0x10, 0x01, 0x01, 0x01, 0x39, 0xac, + 0x8b, 0x98, 0xf5, 0x08, 0xd9, 0xf4, 0x1e, 0x6d, 0xd8, 0xf1, 0xa9, 0x82, 0x96, 0x01, 0x95, 0xfc, + 0xc1, 0x00, 0xda, 0xf4, 0x1e, 0x45, 0xdb, 0xf1, 0xac, 0x89, 0x93, 0xf5, 0x18, 0xf1, 0xa5, 0xdf, + 0xf8, 0xd8, 0xf4, 0x1e, 0x71, 0xd8, 0xf1, 0xa4, 0x84, 0x95, 0x34, 0xfd, 0x06, 0x54, 0xfd, 0x06, + 0x74, 0xfd, 0x06, 0xa9, 0x94, 0xf5, 0x2c, 0x54, 0x7c, 0xf1, 0xac, 0x87, 0x99, 0x49, 0xdb, 0x51, + 0x59, 0x84, 0xab, 0xc3, 0xc5, 0xc7, 0x82, 0xa6, 0xc0, 0xf3, 0xaa, 0xdf, 0xf8, 0xd8, 0xf1, 0xa5, + 0xdf, 0xd8, 0xf1, 0xa0, 0xde, 0xa1, 0xde, 0xdf, 0xdf, 0xdf, 0xa7, 0xde, 0xdf, 0xa4, 0xdf, 0xdf, + 0xdf, 0xa2, 0x95, 0xfc, 0xc0, 0x01, 0xd9, 0x80, 0xc3, 0xc5, 0xc7, 0xa8, 0x83, 0xc1, 0xda, 0x86, + 0xc3, 0xc5, 0xc7, 0xa8, 0x83, 0xc3, 0xd8, 0xf1, 0x9a, 0xfc, 0xc1, 0x04, 0xd9, 0xac, 0x82, 0x96, + 0x01, 0xf3, 0xaa, 0xde, 0xf8, 0xf8, 0xf8, 0xdb, 0xf5, 0xac, 0x8c, 0x9a, 0x18, 0xf3, 0xaa, 0xf9, + 0xd8, 0xac, 0x8a, 0x9a, 0x41, 0xd1, 0xaa, 0xd0, 0xc0, 0xd9, 0xf2, 0xac, 0x85, 0x9a, 0x41, 0xdb, + 0xd1, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xf4, 0x1e, 0xd6, 0xd8, 0xf3, 0xbc, 0xbc, 0xbd, 0xbd, + 0xbe, 0xbe, 0xa5, 0x85, 0x9c, 0x10, 0xd8, 0xf1, 0xb8, 0xb0, 0xb4, 0xa7, 0x88, 0x9e, 0xf7, 0x7a, + 0xf9, 0xd9, 0xf4, 0x20, 0x0d, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xbb, 0xa2, 0xf9, 0xda, 0xbe, 0xf4, + 0x20, 0x0d, 0xd8, 0xf1, 0xbc, 0xbc, 0xbc, 0xb3, 0x80, 0xc6, 0xaf, 0xde, 0xd0, 0xdf, 0xbc, 0xb2, + /* bank # 31 */ + 0x84, 0xbd, 0xbd, 0xbd, 0xb7, 0x9f, 0xa0, 0x60, 0xbc, 0xbc, 0xbc, 0xb3, 0x85, 0x90, 0xaf, 0x01, + 0x9f, 0x46, 0x8f, 0xa2, 0x0e, 0x85, 0x92, 0xaf, 0xd0, 0x29, 0x9f, 0x52, 0xa5, 0x08, 0x34, 0xa0, + 0xfb, 0x86, 0x95, 0xaf, 0x29, 0xda, 0xa6, 0xde, 0xf4, 0x1f, 0x41, 0xd8, 0xf1, 0xa0, 0xfa, 0xf9, + 0xda, 0xa6, 0xde, 0xf4, 0x1f, 0x41, 0xd8, 0xf1, 0xa6, 0xf8, 0x96, 0xaf, 0x19, 0xd9, 0xa3, 0xde, + 0xf8, 0xd8, 0xf1, 0x85, 0x94, 0xaf, 0x31, 0xd9, 0xa3, 0xde, 0xf8, 0xf8, 0x80, 0xa0, 0xc5, 0xd8, + 0x85, 0x96, 0xaf, 0x31, 0xd9, 0xa3, 0xde, 0xf8, 0xf8, 0xf8, 0x80, 0xa5, 0xc0, 0x86, 0xc3, 0xd8, + 0xa8, 0xdf, 0xa1, 0xde, 0x85, 0x91, 0xaf, 0x0c, 0x0d, 0xf5, 0x8f, 0x9f, 0xaf, 0x2c, 0x54, 0xf1, + 0x97, 0xfc, 0xc0, 0x04, 0xdb, 0x8f, 0xaf, 0x51, 0xa8, 0xdf, 0xf8, 0xd8, 0x98, 0xfc, 0xc0, 0x08, + 0xd9, 0xf4, 0x1f, 0xa9, 0xd8, 0xf1, 0xfc, 0xc0, 0x0c, 0xd9, 0xf4, 0x1f, 0xd2, 0xd8, 0xf1, 0x93, + 0xfc, 0xc0, 0x09, 0xd9, 0xa4, 0xde, 0xa8, 0xde, 0xf8, 0xf8, 0xd8, 0xfc, 0xc0, 0x04, 0xd9, 0x85, + 0xa1, 0xc1, 0xa7, 0xde, 0xf8, 0xd8, 0xf4, 0x1f, 0xeb, 0xd8, 0xf1, 0xa4, 0xf8, 0x82, 0x91, 0xaf, + 0x31, 0xdb, 0x9f, 0x71, 0x92, 0x41, 0xa7, 0xde, 0xd8, 0x84, 0x94, 0xaf, 0x19, 0xd9, 0xa8, 0xde, + 0xf8, 0xf8, 0xf8, 0xa3, 0xdf, 0xd8, 0x93, 0xfc, 0xc0, 0x0a, 0xd9, 0xa8, 0xde, 0xf8, 0xd8, 0xf4, + 0x1f, 0xeb, 0xd8, 0xf1, 0xa4, 0xf8, 0xa3, 0xfa, 0xf9, 0xd1, 0xdb, 0x88, 0x94, 0xaf, 0x41, 0x88, + 0xa1, 0xc2, 0xd8, 0x93, 0xfc, 0xc0, 0x0a, 0xd9, 0xa8, 0xde, 0xf8, 0xd8, 0xf1, 0x91, 0xfc, 0xc0, + 0x04, 0xd9, 0xa7, 0xfa, 0xa3, 0xfa, 0xaf, 0xd0, 0xdf, 0xf8, 0xf8, 0xd8, 0xaf, 0xd0, 0xfa, 0xf9, + /* bank # 32 */ + 0xd1, 0xb0, 0xbc, 0xb4, 0xbd, 0xb8, 0xbe, 0xda, 0xf3, 0xa5, 0x85, 0x9d, 0x08, 0xd8, 0xf1, 0xf1, + 0xa7, 0xde, 0xf7, 0x84, 0x9f, 0x6a, 0x87, 0xf1, 0xd4, 0xfd, 0x3e, 0xf9, 0xd9, 0xf4, 0x20, 0x3d, + 0xd8, 0xf0, 0xf7, 0xa7, 0x88, 0x9f, 0x52, 0xf9, 0xd9, 0xf4, 0x20, 0x3d, 0xd8, 0xf2, 0xbb, 0xa0, + 0xf9, 0xda, 0xf4, 0x20, 0x3d, 0xd8, 0xf2, 0xb3, 0x80, 0xc4, 0xf4, 0x75, 0xd1, 0xd8, 0xf0, 0xb1, + 0xb5, 0xba, 0x8a, 0x9a, 0xa7, 0xf0, 0x2c, 0x50, 0x78, 0xf2, 0xa5, 0xde, 0xf8, 0xf8, 0xf1, 0xb5, + 0xb2, 0xa7, 0x87, 0x90, 0x21, 0xdb, 0xb6, 0xb1, 0x80, 0x97, 0x29, 0xd9, 0xf2, 0xa5, 0xf8, 0xd8, + 0xbb, 0xb2, 0xb6, 0xbe, 0xa1, 0xf8, 0xf9, 0xd1, 0xbe, 0xbe, 0xbe, 0xba, 0xda, 0xa5, 0xde, 0xd8, + 0xa7, 0x82, 0x95, 0x65, 0xd1, 0x85, 0xa2, 0xd0, 0xc1, 0xd9, 0xb5, 0xa7, 0x86, 0x93, 0x31, 0xdb, + 0xd1, 0xf4, 0x20, 0x8d, 0xd8, 0xf3, 0xb8, 0xb0, 0xb4, 0xa5, 0x85, 0x9c, 0x18, 0xd8, 0xf1, 0xba, + 0xb2, 0xb6, 0x81, 0x96, 0xa1, 0xf8, 0xf9, 0xb9, 0xa6, 0xda, 0xc3, 0xc5, 0xc7, 0xd9, 0x2d, 0x4d, + 0x6d, 0xd8, 0xba, 0x8a, 0xaa, 0xf8, 0xf9, 0xb9, 0xae, 0xda, 0xc3, 0xc5, 0xc7, 0xd9, 0x2d, 0x4d, + 0x6d, 0xd8, 0xba, 0x88, 0xa8, 0xf8, 0xf9, 0xa7, 0xda, 0xc3, 0xc5, 0xc7, 0xd9, 0x2d, 0x4d, 0x6d, + 0xd8, 0xf2, 0xb0, 0xb9, 0xa3, 0xfa, 0xf9, 0xd1, 0xda, 0xb8, 0x8f, 0xa7, 0xc0, 0xf9, 0xb5, 0x87, + 0x93, 0xf6, 0x0a, 0xf2, 0xb4, 0xa4, 0x84, 0x97, 0x24, 0xa4, 0x84, 0x9e, 0x3c, 0xd8, 0xf3, 0xbe, + 0xbe, 0xbb, 0xae, 0xf8, 0xf9, 0xd1, 0xbe, 0xbe, 0xb0, 0xb4, 0xb8, 0xda, 0xa5, 0x85, 0x9e, 0x00, + 0xd8, 0xf1, 0xbc, 0xbc, 0xbd, 0xbd, 0x8e, 0x9e, 0xa7, 0x59, 0xd1, 0xbc, 0xbc, 0xbd, 0xbd, 0xda, + /* bank # 33 */ + 0x85, 0x9e, 0xa5, 0x08, 0xd8, 0xf1, 0xbc, 0xbc, 0x8e, 0xbe, 0xbe, 0xae, 0xd0, 0xc5, 0xbc, 0xbc, + 0xbe, 0xbe, 0xf7, 0xb9, 0xb0, 0xb5, 0xa6, 0x88, 0x95, 0x5a, 0xf9, 0xda, 0xf1, 0xab, 0xf8, 0xd8, + 0xb8, 0xb4, 0xf3, 0x98, 0xfc, 0xc0, 0x04, 0xda, 0xf4, 0x21, 0x7b, 0xd8, 0xf2, 0xa9, 0xd0, 0xf8, + 0x89, 0x9b, 0xa7, 0x51, 0xd9, 0xa9, 0xd0, 0xde, 0xa4, 0x84, 0x9e, 0x2c, 0xd8, 0xa8, 0xfa, 0x88, + 0x9a, 0xa7, 0x29, 0xd9, 0xa8, 0xdf, 0xa4, 0x84, 0x9d, 0x34, 0xd8, 0xa8, 0xd0, 0xf8, 0x88, 0x9a, + 0xa7, 0x51, 0xd9, 0xa8, 0xd0, 0xde, 0xa4, 0x84, 0x9d, 0x2c, 0xd8, 0xa8, 0xd0, 0xfa, 0x88, 0x9a, + 0xa7, 0x79, 0xd9, 0xa8, 0xd0, 0xdf, 0xa4, 0x84, 0x9d, 0x24, 0xd8, 0xf3, 0xa9, 0xd0, 0xf8, 0x89, + 0x9b, 0xa7, 0x51, 0xd9, 0xa9, 0xd0, 0xde, 0xa4, 0x84, 0x9c, 0x2c, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, + 0x52, 0xf9, 0xd9, 0xf4, 0x21, 0xab, 0xd8, 0xf1, 0xb9, 0xa2, 0xfa, 0xf3, 0xb8, 0xa9, 0xd0, 0xfa, + 0x89, 0x9b, 0xa7, 0x79, 0xd9, 0xa9, 0xd0, 0xdf, 0xa4, 0x84, 0x9c, 0x24, 0xd8, 0xf2, 0xa8, 0xf8, + 0x88, 0x9a, 0xa7, 0x01, 0xd9, 0xa8, 0xde, 0xa4, 0x84, 0x9d, 0x3c, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, + 0x42, 0xf9, 0xd9, 0xf4, 0x21, 0xf2, 0xd8, 0xf3, 0xa9, 0xf8, 0x89, 0x9b, 0xa7, 0x01, 0xd9, 0xa9, + 0xde, 0xa4, 0x84, 0x9c, 0x3c, 0xd8, 0xa9, 0xfa, 0x89, 0x9b, 0xa7, 0x29, 0xd9, 0xa9, 0xdf, 0xa4, + 0x84, 0x9c, 0x34, 0xd8, 0xf2, 0xa9, 0xfa, 0x89, 0x9b, 0xa7, 0x29, 0xd9, 0xa9, 0xdf, 0xa4, 0x84, + 0x9e, 0x34, 0xd8, 0xa9, 0xd0, 0xfa, 0x89, 0x9b, 0xa7, 0x79, 0xd9, 0xa9, 0xd0, 0xdf, 0xa4, 0x84, + 0x9e, 0x24, 0xd8, 0xf1, 0xa7, 0xde, 0xf2, 0x84, 0xca, 0x97, 0xa4, 0x24, 0xa5, 0x94, 0xf6, 0x0a, + /* bank # 34 */ + 0xf7, 0x85, 0x02, 0xf8, 0xf9, 0xd1, 0xd9, 0xf6, 0x9b, 0x02, 0xd8, 0xa7, 0xb1, 0x82, 0x95, 0x62, + 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x23, 0xe7, 0xd8, 0xf0, 0xb0, 0x85, 0xa4, 0xd0, 0xc0, 0xdd, 0xf2, + 0xc0, 0xdc, 0xf6, 0xa7, 0x9f, 0x02, 0xf9, 0xd9, 0xf3, 0xa5, 0xde, 0xda, 0xf0, 0xdd, 0xf2, 0xc8, + 0xdc, 0xd8, 0x85, 0x95, 0xa5, 0x00, 0xd9, 0x86, 0xf0, 0xdd, 0xf2, 0xca, 0xcc, 0xce, 0xdc, 0xd8, + 0x85, 0x00, 0xd9, 0x80, 0xf0, 0xdd, 0xf2, 0xcc, 0xc6, 0xce, 0x85, 0xca, 0xcc, 0xce, 0xdc, 0xd8, + 0x85, 0x00, 0xd9, 0xb1, 0x89, 0xf0, 0xdd, 0xf2, 0xc2, 0xca, 0xc4, 0xdc, 0xd8, 0xb0, 0x85, 0x00, + 0xd9, 0x81, 0xf0, 0xdd, 0xf2, 0xc6, 0xce, 0x82, 0xc0, 0xc8, 0xdc, 0xd8, 0x85, 0x00, 0xb1, 0xd9, + 0x86, 0xf0, 0xdd, 0xf1, 0xc2, 0xc4, 0xc6, 0xdc, 0xd8, 0xb0, 0xf2, 0x85, 0x00, 0xd9, 0xb2, 0x87, + 0xf0, 0xdd, 0xf1, 0xc2, 0xc4, 0xc6, 0xf2, 0xbc, 0xb0, 0x81, 0xc0, 0xdc, 0xbc, 0xbc, 0xbc, 0xd8, + 0xb0, 0x85, 0x00, 0xb1, 0xd9, 0x8f, 0xf0, 0xdd, 0xf2, 0xc2, 0xc4, 0xc6, 0xdc, 0xd8, 0xb0, 0x85, + 0x00, 0xd9, 0xb1, 0x8e, 0xf0, 0xdd, 0xf1, 0xc2, 0xc4, 0xc6, 0xf2, 0xbc, 0xb0, 0x81, 0xc0, 0xdc, + 0xbc, 0xbc, 0xbc, 0xd8, 0xb0, 0x85, 0x00, 0xd9, 0x82, 0xf0, 0xdd, 0xf2, 0xc2, 0xca, 0xc4, 0xdc, + 0xd8, 0x85, 0x00, 0xd8, 0xf2, 0x85, 0x00, 0xd9, 0xb1, 0x8a, 0xf0, 0xdd, 0xf1, 0xc2, 0xc4, 0xc6, + 0xdc, 0xd8, 0xb0, 0xf2, 0x85, 0x00, 0xd9, 0xb1, 0xf0, 0xdd, 0xf1, 0x82, 0xc4, 0xdc, 0xd8, 0xb0, + 0xf3, 0xa5, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x23, 0x69, 0xd8, 0xf3, 0x85, 0x95, 0xa5, 0x00, 0x00, + 0xd9, 0xbe, 0xf2, 0xba, 0xae, 0xde, 0xbe, 0xbe, 0xbe, 0xbc, 0xb2, 0x81, 0xf0, 0xdd, 0xf3, 0xc8, + /* bank # 35 */ + 0xdc, 0xbc, 0xbc, 0xbc, 0xd8, 0xb0, 0xb8, 0x85, 0xa5, 0x00, 0xd9, 0xf2, 0xbe, 0xbe, 0xaa, 0xde, + 0xbe, 0xbe, 0xbc, 0xbc, 0x8a, 0xf0, 0xdd, 0xf3, 0xc0, 0xdc, 0xbc, 0xbc, 0xd8, 0x85, 0xa5, 0x00, + 0xd9, 0xb9, 0xf2, 0xa3, 0xd0, 0xde, 0xb2, 0x85, 0xf0, 0xdd, 0xf3, 0xc8, 0xdc, 0xd8, 0xb0, 0x85, + 0xb8, 0xa5, 0x00, 0xd9, 0xb3, 0x8a, 0xf0, 0xdd, 0xf3, 0xc0, 0xdc, 0xd8, 0xb0, 0x85, 0x00, 0xd9, + 0x8f, 0xf0, 0xdd, 0xf3, 0xc4, 0xdc, 0xd8, 0x85, 0x00, 0x00, 0x00, 0xd9, 0xbc, 0xbc, 0xb3, 0x8e, + 0xf0, 0xdd, 0xf3, 0xc0, 0xf1, 0xc2, 0xdc, 0xbc, 0xbc, 0xd8, 0xf3, 0xb0, 0x85, 0x00, 0xd9, 0xbc, + 0xbc, 0x8e, 0xf0, 0xdd, 0xf3, 0xc4, 0xdc, 0xbc, 0xbc, 0xd8, 0xf3, 0xb0, 0x8e, 0xf4, 0xb8, 0xa7, + 0xd0, 0xc0, 0xd8, 0x87, 0xf3, 0xb9, 0xa2, 0xc6, 0xa6, 0xc4, 0xf7, 0xb5, 0x8e, 0x96, 0x06, 0xf8, + 0xf9, 0xd1, 0xda, 0xf4, 0x23, 0x72, 0xd8, 0xf3, 0x8e, 0xc0, 0xf9, 0xb1, 0x86, 0x96, 0xf7, 0x0a, + 0xdf, 0xf3, 0x30, 0xfd, 0x08, 0xa2, 0x82, 0x10, 0xf0, 0xdd, 0xf3, 0x82, 0xc0, 0xdc, 0xf2, 0xb9, + 0xa3, 0xdf, 0xf4, 0xb1, 0x8c, 0xf3, 0xaf, 0xc1, 0xc3, 0xaf, 0x8f, 0xb4, 0x9d, 0x3e, 0xfd, 0x1e, + 0xb5, 0x9f, 0x30, 0xa6, 0x39, 0xd9, 0xf4, 0x23, 0xe1, 0xd8, 0xf7, 0xb8, 0xb0, 0xb4, 0xa7, 0x84, + 0x9d, 0x1a, 0xf9, 0xd9, 0xf4, 0x23, 0xd4, 0xd8, 0xf1, 0xb9, 0xb1, 0xb5, 0xa6, 0x83, 0x9b, 0x61, + 0xd9, 0xf4, 0x23, 0xe7, 0xd8, 0xf6, 0xb8, 0xb0, 0xb4, 0xa7, 0x84, 0x94, 0x5a, 0xf8, 0xf9, 0xd1, + 0xda, 0xf0, 0xe2, 0xf1, 0xb9, 0xab, 0xde, 0xd8, 0xf2, 0xb1, 0x86, 0xb9, 0xaf, 0xc3, 0xc5, 0xc7, + 0xb8, 0xb0, 0xb4, 0xa7, 0x88, 0x9c, 0xf7, 0x6a, 0xf9, 0xd9, 0xff, 0xd8, 0x72, 0xb9, 0xab, 0xf1, + /* bank # 36 */ + 0xdf, 0xf7, 0x62, 0xf3, 0xf8, 0xf9, 0xd1, 0xda, 0xf1, 0xde, 0xf8, 0xd8, 0xf7, 0xbb, 0xaf, 0x7a, + 0x9d, 0x66, 0x9e, 0x76, 0x9f, 0x76, 0xf1, 0xa1, 0xdf, 0xba, 0xa6, 0xd0, 0xde, 0xbb, 0xf3, 0xa0, + 0xf9, 0xda, 0xff, 0xd8, 0xb3, 0x80, 0xc4, 0xaf, 0xd0, 0xfa, 0xf9, 0xd1, 0xda, 0xbc, 0xbc, 0xbc, + 0xf4, 0x25, 0xaf, 0xd8, 0xf1, 0xb8, 0xbe, 0xbe, 0xae, 0xd0, 0xde, 0xb0, 0x84, 0xba, 0xbe, 0xa7, + 0xc1, 0xf7, 0x88, 0xb4, 0x9d, 0x6e, 0xf9, 0xb2, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xda, 0xf4, + 0x24, 0x84, 0xd8, 0xf1, 0xb8, 0xbe, 0xbe, 0xbe, 0xae, 0xd0, 0x91, 0xfc, 0xc0, 0x00, 0xdb, 0xb6, + 0x95, 0xfc, 0xc1, 0x04, 0xd9, 0xf8, 0xf8, 0xf8, 0xf8, 0xd8, 0xb4, 0x91, 0xfc, 0xc0, 0x04, 0xdb, + 0xb6, 0x95, 0xfc, 0xc1, 0x00, 0xd9, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xd8, 0xba, + 0xbe, 0xf4, 0x24, 0xeb, 0xd8, 0xf1, 0x91, 0xfc, 0xc0, 0x00, 0xdb, 0xb6, 0x95, 0xfc, 0xc1, 0x04, + 0xf5, 0x87, 0x95, 0xa7, 0x3a, 0xf1, 0xf9, 0xd9, 0xaf, 0xde, 0x8f, 0xbe, 0xbe, 0xa1, 0xf4, 0xc1, + 0xf1, 0xa2, 0xf4, 0xc1, 0xf1, 0xbe, 0xbe, 0xd8, 0xb4, 0x91, 0xfc, 0xc0, 0x04, 0xdb, 0xb6, 0x95, + 0xfc, 0xc1, 0x00, 0xd9, 0xaf, 0xde, 0xf8, 0xfd, 0x07, 0x8f, 0x95, 0x10, 0xdf, 0xf8, 0xf8, 0xf8, + 0xa7, 0xde, 0xf8, 0xfd, 0x07, 0xdf, 0xf8, 0xfd, 0x06, 0xdf, 0xf8, 0xfd, 0x04, 0x8f, 0x97, 0xaf, + 0xd0, 0xde, 0x40, 0x48, 0x50, 0xdf, 0xf8, 0x60, 0x8f, 0xbe, 0xbe, 0xa0, 0xd0, 0xf4, 0xc1, 0xf1, + 0xa1, 0xf4, 0xc2, 0xc5, 0xf1, 0xa2, 0xf4, 0xc7, 0xf1, 0xbe, 0xbe, 0xd8, 0xf1, 0xb0, 0x81, 0xa5, + 0xc1, 0xbc, 0x84, 0xb8, 0xbe, 0xbe, 0xa9, 0xc1, 0xf7, 0x88, 0xb4, 0xbd, 0x9d, 0x6e, 0xf9, 0xbc, + /* bank # 37 */ + 0xbd, 0xda, 0xf4, 0x25, 0x38, 0xd8, 0xf1, 0xa9, 0xde, 0xf8, 0xfd, 0x04, 0xdf, 0xf8, 0xfd, 0x05, + 0xbc, 0x8e, 0xbe, 0xae, 0xd0, 0x9a, 0xfc, 0xc0, 0x00, 0xdb, 0x9b, 0xfc, 0xc0, 0x04, 0xd9, 0x99, + 0x40, 0xd8, 0x9a, 0xfc, 0xc0, 0x04, 0xdb, 0x9b, 0xfc, 0xc0, 0x00, 0xd9, 0x99, 0x48, 0xd8, 0xbc, + 0xbc, 0xbc, 0xbe, 0xbe, 0xbe, 0xf4, 0x25, 0xa2, 0xd8, 0xf1, 0x9a, 0xfc, 0xc0, 0x00, 0xdb, 0x9b, + 0xfc, 0xc0, 0x04, 0xf5, 0x89, 0xa9, 0x32, 0xf9, 0xd9, 0xf1, 0xde, 0xf8, 0xfd, 0x02, 0xdf, 0xf8, + 0xfd, 0x07, 0xdf, 0xf8, 0xfd, 0x07, 0xf8, 0xdf, 0x89, 0xba, 0xa0, 0xf4, 0xc0, 0xf1, 0x8b, 0xa1, + 0xd0, 0xf4, 0xc3, 0xf1, 0x89, 0xa2, 0xf4, 0xc2, 0xc5, 0xc7, 0xf1, 0xa3, 0xf4, 0xc7, 0xf1, 0xb8, + 0xd8, 0x9a, 0xfc, 0xc0, 0x04, 0xdb, 0x9b, 0xfc, 0xc0, 0x00, 0xd9, 0xa9, 0xde, 0xf8, 0xfd, 0x02, + 0xdf, 0xf8, 0xfd, 0x07, 0xdf, 0xf8, 0xfd, 0x07, 0xf8, 0xdf, 0xf8, 0xfd, 0x04, 0xf9, 0x89, 0xba, + 0xa0, 0xf4, 0xc0, 0xf1, 0x8b, 0xa1, 0xd0, 0xf4, 0xc3, 0xf1, 0x89, 0xa2, 0xf4, 0xc2, 0xc5, 0xc7, + 0xf1, 0xb8, 0xd8, 0xf1, 0x8a, 0xab, 0xc0, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbe, 0xbe, 0xbe, 0xd8, + 0xf1, 0xb2, 0x80, 0xba, 0xa7, 0xc4, 0xbc, 0xb2, 0x8b, 0xf4, 0x75, 0x6a, 0x8f, 0xb6, 0x9c, 0xf4, + 0x75, 0x76, 0xaf, 0xf4, 0x75, 0x7c, 0x8b, 0xf4, 0x75, 0x6a, 0x8e, 0xb6, 0x9d, 0xf4, 0x75, 0x76, + 0xae, 0xf4, 0x75, 0x7c, 0xb3, 0x81, 0xf4, 0x75, 0x6a, 0x85, 0x94, 0xf4, 0x75, 0x76, 0xbb, 0xa5, + 0xf4, 0x75, 0x7c, 0x80, 0xba, 0xf4, 0x75, 0x6a, 0xb3, 0x8e, 0x9b, 0xf4, 0x75, 0x76, 0xbb, 0xae, + 0xf4, 0x75, 0x7c, 0xb3, 0x83, 0xa3, 0xf4, 0x75, 0x88, 0xf1, 0xb2, 0x8f, 0xb6, 0x9f, 0xbe, 0xbe, + /* bank # 38 */ + 0xb9, 0xaf, 0x7a, 0x8e, 0x9e, 0x7e, 0xf5, 0xb3, 0x85, 0xb7, 0x95, 0x7c, 0x8e, 0x9e, 0x7c, 0xf1, + 0xbc, 0xbc, 0xbd, 0xbd, 0xb1, 0xb5, 0x8f, 0x9f, 0xaf, 0xd0, 0x58, 0x82, 0xaf, 0x01, 0x2d, 0x55, + 0x86, 0xaf, 0x42, 0x4e, 0x76, 0x82, 0xa2, 0x00, 0x2c, 0x54, 0x84, 0xbd, 0xb6, 0x90, 0xaf, 0x51, + 0xbd, 0xbd, 0xbd, 0xb5, 0x9f, 0x06, 0xa4, 0xd0, 0x48, 0x8f, 0xaf, 0xd0, 0x0a, 0x84, 0x74, 0xa4, + 0xd0, 0x3e, 0x80, 0x93, 0xaf, 0x39, 0xd1, 0xab, 0xd9, 0xfa, 0xda, 0xdf, 0xd8, 0xba, 0xad, 0xfa, + 0x83, 0x9b, 0xa7, 0x69, 0xdb, 0xb2, 0x8d, 0xb6, 0x9d, 0x69, 0xf4, 0x26, 0x62, 0xd8, 0xf1, 0xad, + 0xde, 0xdf, 0xd8, 0xf0, 0xbc, 0xb2, 0x81, 0xbd, 0xb6, 0x91, 0xbb, 0xa6, 0x3c, 0x11, 0x0c, 0x58, + 0x2c, 0x50, 0xf1, 0xbc, 0xbc, 0xbc, 0xb3, 0x86, 0xbd, 0xbd, 0xbd, 0xb7, 0x96, 0xa6, 0x2c, 0x54, + 0x7c, 0x9b, 0x71, 0x97, 0xa5, 0xd0, 0x2a, 0xf0, 0x50, 0x78, 0xf1, 0xd8, 0xb8, 0xac, 0xde, 0xf8, + 0xf5, 0xb0, 0x8c, 0xb7, 0x93, 0x06, 0xf1, 0xf9, 0xaf, 0xda, 0xf8, 0xd9, 0xde, 0xd8, 0xb3, 0xb6, + 0xba, 0x86, 0xa7, 0xc2, 0xf4, 0x75, 0x90, 0x93, 0xf0, 0x71, 0x71, 0x60, 0x84, 0x92, 0xf4, 0x75, + 0x76, 0xf1, 0xa4, 0xf4, 0x75, 0x7c, 0x83, 0xa3, 0xf4, 0x75, 0x88, 0xb3, 0x86, 0xa7, 0xc4, 0xf4, + 0x75, 0x90, 0x95, 0xf0, 0x71, 0x71, 0x60, 0x86, 0x92, 0xf4, 0x75, 0x76, 0xa6, 0xf4, 0x75, 0x7c, + 0x85, 0xa5, 0xf4, 0x75, 0x88, 0xb3, 0x86, 0xa7, 0xc6, 0xf4, 0x75, 0x90, 0x9f, 0xf0, 0x71, 0x71, + 0x60, 0x88, 0x92, 0xf4, 0x75, 0x76, 0xa8, 0xf4, 0x75, 0x7c, 0x8f, 0xaf, 0xf4, 0x75, 0x88, 0xf5, + 0xb2, 0x84, 0x94, 0xb9, 0xaf, 0x7c, 0x86, 0x96, 0x7c, 0x88, 0x98, 0x7c, 0xf1, 0xb1, 0x8f, 0xb5, + /* bank # 39 */ + 0x9f, 0xa5, 0x30, 0x85, 0x18, 0xf0, 0x9a, 0x3c, 0x99, 0x18, 0xf1, 0xbc, 0xbc, 0xb2, 0x84, 0xb9, + 0xaf, 0xc3, 0xc5, 0xc7, 0xba, 0xb6, 0xbc, 0xbc, 0xa7, 0x8b, 0xb5, 0x9f, 0x2d, 0x55, 0x7d, 0xf5, + 0xa7, 0x87, 0xb6, 0x97, 0x2c, 0x54, 0x7c, 0xf0, 0xac, 0x81, 0x9c, 0x0c, 0x97, 0x28, 0x9c, 0x14, + 0x97, 0x30, 0x9c, 0x1c, 0x97, 0x38, 0xf1, 0xb1, 0x8f, 0xab, 0xc3, 0xc5, 0xc7, 0xa7, 0xb2, 0x81, + 0x9c, 0x59, 0xdb, 0x51, 0xaa, 0xde, 0xf4, 0x27, 0x5f, 0xd8, 0xf1, 0xac, 0xb1, 0x8e, 0x9c, 0x48, + 0xfd, 0x02, 0xb2, 0x8b, 0x02, 0xaa, 0xde, 0xa7, 0x8c, 0x11, 0xdb, 0x19, 0xda, 0xaa, 0xf8, 0xd8, + 0xf1, 0xb5, 0xbd, 0xbd, 0x9b, 0xfc, 0xc1, 0x03, 0xbd, 0xbd, 0xd9, 0xf4, 0x28, 0xdf, 0xd8, 0xf1, + 0xb2, 0xbc, 0xbc, 0x84, 0xb8, 0xbe, 0xae, 0xc3, 0xc5, 0xc7, 0xb0, 0xbc, 0xbc, 0xbc, 0xb4, 0xbd, + 0xf0, 0x8a, 0x9e, 0xaf, 0x6c, 0x99, 0x61, 0x8a, 0x19, 0x9e, 0x74, 0x99, 0x69, 0x8a, 0x39, 0x9e, + 0x7c, 0x99, 0x71, 0x8a, 0x59, 0xf1, 0x8f, 0x9f, 0xaa, 0x28, 0xfd, 0x01, 0x54, 0xfd, 0x01, 0x7c, + 0xfd, 0x01, 0x8e, 0xa9, 0xc2, 0xc5, 0xc7, 0xf0, 0x8a, 0x9a, 0xa7, 0x04, 0x28, 0x50, 0xf1, 0x87, + 0x97, 0xaf, 0x09, 0x8f, 0xb5, 0xbd, 0xbd, 0xbd, 0x9b, 0x1e, 0xb4, 0xbd, 0x97, 0xa7, 0x20, 0x8b, + 0xba, 0xa7, 0xc1, 0xc3, 0xc5, 0xbd, 0xb6, 0x90, 0xfc, 0xc2, 0x00, 0xbd, 0xbd, 0xbd, 0xd9, 0xf4, + 0x28, 0x6c, 0xd8, 0xf1, 0xb2, 0x86, 0xb6, 0x97, 0xa7, 0x4a, 0x99, 0xf4, 0x75, 0x96, 0x9a, 0xf4, + 0x75, 0x76, 0x8a, 0xaa, 0xf4, 0x75, 0x88, 0xf1, 0x86, 0x97, 0xa7, 0x52, 0x9b, 0xf4, 0x75, 0x96, + 0x9c, 0xf4, 0x75, 0x76, 0x8c, 0xac, 0xf4, 0x75, 0x88, 0xf1, 0x86, 0x97, 0xa7, 0x5a, 0x9d, 0xf4, + /* bank # 40 */ + 0x75, 0x96, 0x9e, 0xf4, 0x75, 0x76, 0x8e, 0xae, 0xf4, 0x75, 0x88, 0xf1, 0x89, 0xa9, 0xc2, 0xc5, + 0xc7, 0x87, 0xc3, 0x8b, 0xab, 0xc2, 0xc5, 0xc7, 0x87, 0xc5, 0x8d, 0xad, 0xc2, 0xc5, 0xc7, 0x87, + 0xc7, 0xb8, 0xae, 0xde, 0x8a, 0xb4, 0x9e, 0x64, 0xfd, 0x01, 0x8c, 0x64, 0xfd, 0x01, 0x8e, 0x64, + 0xfd, 0x01, 0xb0, 0xf0, 0x8d, 0x9e, 0xaf, 0x6c, 0x9c, 0x61, 0x8d, 0x19, 0x9e, 0x74, 0x9c, 0x69, + 0x8d, 0x39, 0x9e, 0x7c, 0x9c, 0x71, 0x8d, 0x59, 0xf1, 0x8f, 0x9f, 0xad, 0x28, 0xfd, 0x01, 0x54, + 0xfd, 0x01, 0x7c, 0xfd, 0x01, 0x8e, 0xac, 0xc2, 0xc5, 0xc7, 0xf0, 0x8d, 0x9d, 0xa8, 0x04, 0x28, + 0x50, 0xf1, 0x88, 0x98, 0xaf, 0x09, 0x8f, 0x9b, 0x1e, 0x98, 0xa8, 0x20, 0xd8, 0xf1, 0xb8, 0xb1, + 0xb4, 0xbc, 0xbc, 0xbc, 0x84, 0xaf, 0xc7, 0x87, 0xc1, 0xb3, 0x83, 0xc1, 0xbc, 0xb0, 0x8f, 0x9f, + 0xaf, 0x49, 0xda, 0xf4, 0x28, 0x9c, 0xd8, 0xf5, 0x91, 0x7a, 0xf1, 0x9f, 0xfc, 0xc0, 0x03, 0xdb, + 0x90, 0xfc, 0xc0, 0x00, 0xd9, 0xa1, 0xde, 0xf8, 0xd8, 0xf4, 0x28, 0xac, 0xd8, 0xf5, 0x91, 0x72, + 0xf1, 0x9f, 0xfc, 0xc0, 0x03, 0xd9, 0xa1, 0xde, 0xdf, 0xa0, 0xde, 0xdf, 0xd8, 0xf1, 0xa1, 0xf8, + 0xf9, 0xd1, 0xa0, 0xda, 0xf8, 0xd9, 0xfa, 0xd8, 0x80, 0x90, 0xaf, 0x11, 0xdb, 0xa1, 0xde, 0x91, + 0xfc, 0xc1, 0x04, 0xd9, 0xa1, 0xf8, 0xdf, 0xa0, 0xde, 0xd8, 0x80, 0x90, 0xaf, 0x39, 0xd9, 0xa0, + 0xde, 0xdf, 0xa1, 0xdf, 0xd8, 0xf1, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbe, 0xbe, 0xbe, 0xd8, + 0xf1, 0xb1, 0xb5, 0xb9, 0xa6, 0xf8, 0x8a, 0xbb, 0xa4, 0xc3, 0xa0, 0xc5, 0xb9, 0x86, 0x96, 0xaf, + 0x21, 0xd9, 0xf4, 0x30, 0x26, 0xd8, 0xf1, 0xa6, 0xde, 0xa1, 0xde, 0xdf, 0xdf, 0xa0, 0xde, 0xdf, + /* bank # 41 */ + 0xdf, 0xdf, 0xab, 0xde, 0xac, 0xde, 0xb3, 0x8c, 0xbb, 0xa4, 0xd0, 0xc4, 0xa0, 0xd0, 0xc6, 0xb8, + 0xbe, 0xbe, 0xbe, 0x83, 0xa9, 0xc1, 0xf2, 0xbc, 0xbc, 0x82, 0xc3, 0x81, 0xc5, 0xf8, 0xf1, 0xb0, + 0xbc, 0xbd, 0xbd, 0x9b, 0xfc, 0xc1, 0x03, 0xb4, 0xbd, 0xd9, 0xf4, 0x29, 0x79, 0xd8, 0xf1, 0xaa, + 0xde, 0x99, 0xfc, 0xc1, 0x00, 0xd9, 0xaa, 0xfa, 0xdb, 0x8a, 0x9a, 0xa9, 0x39, 0xaa, 0xde, 0xf8, + 0xd8, 0xf5, 0xa2, 0x89, 0x92, 0x3a, 0xf1, 0x92, 0xfc, 0xc0, 0x03, 0xda, 0xdf, 0xd9, 0xfa, 0xa2, + 0x82, 0xdb, 0x31, 0xdf, 0xaa, 0xde, 0xf8, 0xd8, 0x99, 0xfc, 0xc1, 0x03, 0xd9, 0xaa, 0xdf, 0xd8, + 0xf2, 0x89, 0x99, 0xa9, 0x71, 0xdb, 0xde, 0x41, 0xf1, 0xaa, 0xde, 0xf8, 0xd8, 0x9a, 0xfc, 0xc0, + 0x04, 0xdb, 0xa8, 0xde, 0x98, 0xfc, 0xc1, 0x00, 0xf8, 0xd8, 0xf1, 0xb1, 0xbc, 0xb5, 0xbd, 0xb9, + 0xbe, 0x87, 0x94, 0xaf, 0x19, 0xd9, 0x83, 0xa1, 0xc6, 0xf4, 0x2c, 0x6f, 0xd8, 0xf1, 0x82, 0x9f, + 0xaf, 0xdf, 0x28, 0xfd, 0x03, 0xdf, 0x30, 0xfd, 0x04, 0x8f, 0x9f, 0x34, 0x82, 0x38, 0x1d, 0xa9, + 0xde, 0xd9, 0xf8, 0xda, 0xf4, 0x2a, 0xe0, 0xd8, 0xf1, 0x82, 0x97, 0xaf, 0x51, 0xd9, 0x83, 0xa0, + 0xc7, 0x83, 0xa7, 0xd0, 0xc2, 0xf4, 0x2a, 0x11, 0xd8, 0xf1, 0x82, 0x92, 0xaf, 0x59, 0xda, 0xf4, + 0x2a, 0x11, 0xd8, 0xf5, 0xb3, 0x83, 0xb7, 0x99, 0x1a, 0xf1, 0xf8, 0xf9, 0xd1, 0xda, 0xb1, 0xb5, + 0xf4, 0x2a, 0x11, 0xd8, 0xf5, 0x3a, 0xf1, 0xf8, 0xf9, 0xd1, 0xda, 0xb1, 0xb5, 0xf4, 0x2a, 0x11, + 0xd8, 0xf1, 0xb0, 0xbc, 0xbc, 0xbc, 0x88, 0xaf, 0xc1, 0xf2, 0x89, 0xc5, 0xc7, 0xf9, 0xf9, 0xb1, + 0xbc, 0xb5, 0xb9, 0xf2, 0x8f, 0x9f, 0xaf, 0x71, 0xd9, 0xf1, 0x83, 0xa0, 0xc6, 0xb3, 0x8c, 0xbb, + /* bank # 42 */ + 0xa4, 0xd0, 0xc4, 0xa0, 0xd0, 0xc6, 0xb1, 0xb9, 0xd8, 0xf1, 0x83, 0xac, 0xc6, 0x83, 0xa7, 0xd0, + 0xc4, 0xd8, 0xf1, 0xbc, 0xbc, 0x81, 0xaf, 0xc3, 0xf3, 0x8b, 0xc3, 0xf2, 0xb3, 0x82, 0xc2, 0x81, + 0xc5, 0xf9, 0xf1, 0xb1, 0xbc, 0xbc, 0x83, 0x9f, 0xaf, 0x09, 0xdb, 0x8f, 0x9e, 0x31, 0x83, 0xa1, + 0xc7, 0xa0, 0xdf, 0xd0, 0xde, 0x9f, 0xfc, 0xc2, 0x01, 0xd9, 0xf2, 0xaf, 0xde, 0xf8, 0xf8, 0xf8, + 0x8f, 0xdb, 0x41, 0xd9, 0xf1, 0x8e, 0xb7, 0x91, 0xbb, 0xa2, 0xd0, 0x5c, 0xfd, 0x3f, 0xb5, 0xb9, + 0xd8, 0x8f, 0x93, 0xaf, 0x21, 0xdb, 0x83, 0xa0, 0xc7, 0xd0, 0xde, 0xa1, 0xdf, 0x9f, 0xfc, 0xc2, + 0x01, 0xd9, 0xf2, 0xaf, 0xde, 0xf8, 0xf8, 0xf8, 0x8f, 0xdb, 0x41, 0xd9, 0xf1, 0x8e, 0xb7, 0x91, + 0xbb, 0xa2, 0xd0, 0x5c, 0xfd, 0x3f, 0xb5, 0xb9, 0xd8, 0xf1, 0x9f, 0xfc, 0xc2, 0x01, 0xd9, 0xf4, + 0x2a, 0xaf, 0xd8, 0xf3, 0xbc, 0xbc, 0xaf, 0xd0, 0xb1, 0x8c, 0xc4, 0xf1, 0xb0, 0xbc, 0x8a, 0xaf, + 0xc5, 0xb1, 0xbc, 0x80, 0x93, 0xaf, 0x39, 0xd1, 0xd9, 0xf3, 0xd0, 0xf8, 0xf9, 0xdb, 0xd1, 0xf1, + 0x9f, 0xfc, 0xc1, 0x04, 0xf2, 0x8f, 0x9f, 0xaf, 0x59, 0xf1, 0xa0, 0xdf, 0x83, 0xd0, 0xc6, 0xd8, + 0xf1, 0xa1, 0xd0, 0xde, 0x83, 0x90, 0xaf, 0x69, 0xdb, 0x91, 0x69, 0xf4, 0x2a, 0xc9, 0xd8, 0xf2, + 0x8f, 0x9f, 0x71, 0xd9, 0xf1, 0x83, 0xa1, 0xd0, 0xc6, 0xd8, 0xf1, 0x80, 0x93, 0xaf, 0x19, 0xd1, + 0xd9, 0xf4, 0x2b, 0x4f, 0xd8, 0xf1, 0x79, 0xd1, 0xd9, 0xf4, 0x2b, 0x4f, 0xd8, 0xf4, 0x2c, 0xb0, + 0xd8, 0xf1, 0x82, 0x9d, 0xaf, 0x31, 0xda, 0xf4, 0x2b, 0x11, 0xd8, 0xf1, 0x83, 0xa0, 0xd0, 0xc7, + 0xb6, 0x9d, 0xfc, 0xc2, 0x04, 0xd9, 0xba, 0xad, 0xde, 0xf8, 0xd8, 0xb3, 0x8a, 0xb7, 0x92, 0xbb, + /* bank # 43 */ + 0xaf, 0x19, 0xb1, 0x88, 0xa4, 0xd9, 0xc5, 0xa0, 0xc7, 0xda, 0xc1, 0xa0, 0xc3, 0xd8, 0xf4, 0x2b, + 0x4f, 0xd8, 0xf1, 0xa1, 0xf8, 0xf9, 0xd1, 0xda, 0xf4, 0x2b, 0x4f, 0xd8, 0xf1, 0xba, 0xad, 0xf8, + 0xf9, 0xd1, 0xd9, 0x83, 0xb9, 0xa0, 0xc6, 0xab, 0xc6, 0xb3, 0x8d, 0xbb, 0xa4, 0xd0, 0xc4, 0xa0, + 0xd0, 0xc6, 0xf4, 0x2b, 0x4f, 0xd8, 0xf1, 0x83, 0xb9, 0xa0, 0xd0, 0xc7, 0xb3, 0x8a, 0xb7, 0x92, + 0xbb, 0xaf, 0x19, 0xb1, 0xa4, 0xd9, 0x89, 0xc3, 0xa0, 0xc5, 0xda, 0x88, 0xc1, 0xa0, 0xc3, 0xd8, + 0xf1, 0xb1, 0x85, 0xba, 0xbe, 0xaf, 0xc2, 0x84, 0xc7, 0x82, 0xc1, 0xc3, 0xb2, 0xbc, 0xb6, 0xbd, + 0xa7, 0xdf, 0xdf, 0x8f, 0x92, 0xa7, 0x01, 0xd9, 0xf4, 0x2b, 0x91, 0xd8, 0xf1, 0x09, 0xd9, 0xf4, + 0x2b, 0x78, 0xd8, 0xf1, 0xfa, 0xf4, 0x2b, 0xc0, 0xd8, 0xf1, 0x51, 0xd9, 0xf4, 0x2b, 0x85, 0xd8, + 0xf1, 0xfa, 0xf4, 0x2b, 0xc0, 0xd8, 0xf1, 0x19, 0xd9, 0xd0, 0xf8, 0xda, 0xfa, 0xd8, 0xf4, 0x2b, + 0xc0, 0xd8, 0xf1, 0x93, 0x21, 0xd9, 0xf4, 0x2b, 0xa5, 0xd8, 0xf1, 0x09, 0xd9, 0xd0, 0xf8, 0xda, + 0xfa, 0xd8, 0xf4, 0x2b, 0xc0, 0xd8, 0xf1, 0x71, 0xd9, 0xd0, 0xf8, 0xf4, 0x2b, 0xc0, 0xd8, 0xf1, + 0x59, 0xd9, 0xd0, 0xf8, 0xf4, 0x2b, 0xc0, 0xd8, 0xf1, 0x94, 0x01, 0xd9, 0xd0, 0xf8, 0xda, 0xfa, + 0xd8, 0xf1, 0xb0, 0xbc, 0xbc, 0x88, 0xa7, 0xc0, 0xb1, 0xbc, 0x89, 0xd0, 0xc1, 0x82, 0xaf, 0xd0, + 0xc5, 0xb2, 0xbc, 0xb5, 0xbd, 0x9b, 0xfc, 0xc1, 0x00, 0xb6, 0xbd, 0xbd, 0xbd, 0xdb, 0x97, 0xfc, + 0xc3, 0x04, 0xfc, 0xc0, 0x00, 0xfc, 0xc2, 0x04, 0xd9, 0xa7, 0xdf, 0xf8, 0xdf, 0xd8, 0xf1, 0x8f, + 0x94, 0xa7, 0x71, 0xd9, 0xf4, 0x2c, 0x09, 0xd8, 0xf1, 0x95, 0x41, 0xd9, 0xf4, 0x2c, 0x09, 0xd8, + /* bank # 44 */ + 0xf1, 0x94, 0x09, 0xdb, 0x39, 0xd9, 0xdf, 0xdf, 0xf8, 0xd8, 0xf1, 0x97, 0xfc, 0xc1, 0x04, 0xb1, + 0xbc, 0xbc, 0xbc, 0x83, 0xb9, 0xbe, 0xbe, 0xbe, 0xa0, 0xd9, 0xc6, 0xda, 0xde, 0xd8, 0xfc, 0xc2, + 0x04, 0xd0, 0xd9, 0xc7, 0xda, 0xdf, 0xd8, 0x8e, 0xb5, 0xbd, 0x9b, 0xaf, 0x4c, 0xbd, 0xbd, 0x9f, + 0xfc, 0xc1, 0x00, 0xd9, 0xf4, 0x2c, 0xb0, 0xd8, 0xf0, 0xb3, 0x86, 0xb6, 0x9a, 0xbb, 0xab, 0x2c, + 0x50, 0x78, 0xf1, 0xba, 0xaa, 0xc3, 0xc5, 0xc7, 0xb8, 0xad, 0xf8, 0xf9, 0xd1, 0xda, 0xde, 0xb3, + 0x8e, 0xbb, 0xab, 0xc7, 0xd8, 0xb3, 0x8e, 0xb7, 0x9b, 0xba, 0xa7, 0x69, 0xd9, 0xb1, 0x83, 0xb5, + 0x90, 0x79, 0xdb, 0xd1, 0xb9, 0xa0, 0xd0, 0xdf, 0xa1, 0xd0, 0xc6, 0xd8, 0xf4, 0x2c, 0xb0, 0xd8, + 0xf1, 0xb0, 0xbc, 0x81, 0xb9, 0xaf, 0xc0, 0xb0, 0x88, 0xc1, 0x87, 0xc1, 0xb1, 0xbc, 0xbc, 0xbc, + 0xb5, 0xbd, 0xbd, 0x9b, 0xfc, 0xc1, 0x00, 0xbd, 0xbd, 0xdb, 0x9f, 0xfc, 0xc0, 0x04, 0x8f, 0x9e, + 0x2d, 0x8d, 0x9f, 0x31, 0xd9, 0xa1, 0xde, 0x83, 0xa0, 0xc6, 0xaf, 0xde, 0xf8, 0xb3, 0x83, 0x9f, + 0xf5, 0x06, 0xf1, 0xdb, 0xfc, 0xc1, 0x04, 0xd9, 0xb8, 0xbe, 0xa1, 0xdf, 0xf8, 0xbe, 0xbe, 0xbe, + 0xd8, 0xf5, 0xb3, 0x89, 0xb7, 0x93, 0xbb, 0xa9, 0x66, 0x8b, 0xaf, 0x02, 0xf1, 0x9f, 0xfc, 0xc0, + 0x03, 0xd9, 0x8f, 0xa9, 0xd0, 0xc0, 0xd8, 0x89, 0x99, 0xa3, 0x34, 0xaf, 0xde, 0xf8, 0xf5, 0x83, + 0x9f, 0x06, 0xf1, 0xfc, 0xc1, 0x04, 0xdb, 0x95, 0x71, 0xa2, 0xd0, 0xde, 0xd8, 0xb0, 0x8d, 0xb9, + 0xa1, 0xd0, 0xc7, 0x8f, 0xb4, 0x9f, 0xaf, 0x11, 0xd9, 0xa1, 0xd0, 0xc7, 0xd8, 0xf1, 0xb3, 0x89, + 0xbb, 0xaf, 0xc6, 0xf9, 0xf5, 0x8f, 0xb7, 0x93, 0x06, 0xf1, 0x9f, 0xfc, 0xc1, 0x03, 0xdb, 0x83, + /* bank # 45 */ + 0xa9, 0xc0, 0xd8, 0xa3, 0xde, 0xb9, 0xa0, 0xd0, 0xde, 0xba, 0xaa, 0xf8, 0xf9, 0xd1, 0xda, 0xf4, + 0x2d, 0x83, 0xd8, 0xf1, 0xb9, 0xb1, 0xb5, 0xaf, 0x83, 0x90, 0x61, 0xdb, 0x69, 0x79, 0x91, 0x69, + 0xf4, 0x2d, 0x7a, 0xd8, 0xf1, 0xdf, 0xf8, 0xa0, 0xfa, 0xf9, 0xd1, 0xd9, 0xaf, 0xdf, 0xd8, 0xaf, + 0x8c, 0x95, 0x69, 0xd9, 0xdf, 0xd8, 0xaf, 0x85, 0x9c, 0x31, 0xdb, 0x9f, 0xfc, 0xc1, 0x00, 0xda, + 0xf4, 0x2d, 0x57, 0xd8, 0xf1, 0x83, 0xa0, 0xd0, 0xc6, 0xaf, 0x8a, 0x9e, 0x11, 0xf8, 0xd9, 0xa0, + 0xd0, 0x80, 0x9c, 0x48, 0xd8, 0xaa, 0xde, 0xd8, 0xf1, 0xb3, 0x85, 0xb7, 0x95, 0xaf, 0x71, 0xb1, + 0xb5, 0xd9, 0xa0, 0xd0, 0xde, 0xd8, 0xf1, 0x83, 0xaf, 0xc6, 0xf8, 0x8f, 0x94, 0x1d, 0xdb, 0x90, + 0xfc, 0xc0, 0x00, 0xa0, 0xd0, 0xde, 0xd8, 0xf4, 0x2d, 0x83, 0xd8, 0xf1, 0x61, 0xd1, 0xaa, 0xd9, + 0xde, 0xda, 0xf8, 0xd8, 0xf1, 0xb1, 0x88, 0xbb, 0xa4, 0xd0, 0xc5, 0xa0, 0xd0, 0xc7, 0xb5, 0x90, + 0xfc, 0xc2, 0x00, 0xd9, 0xb2, 0x8e, 0xc6, 0xa4, 0xd0, 0xc5, 0xba, 0xae, 0xde, 0xf4, 0x2d, 0xb2, + 0xd8, 0xf1, 0x84, 0xb4, 0x9f, 0xba, 0xa7, 0x69, 0xda, 0xae, 0xf8, 0xf4, 0x2d, 0xb2, 0xd8, 0xf1, + 0xae, 0xde, 0xd8, 0xf1, 0xb1, 0x81, 0xb5, 0x9e, 0xbb, 0xaf, 0x02, 0xb7, 0x94, 0x26, 0xb3, 0x81, + 0xb5, 0x9d, 0xa1, 0x02, 0xb7, 0x90, 0x26, 0x8f, 0x91, 0xa1, 0x00, 0x2c, 0xb1, 0x80, 0x94, 0xaf, + 0x12, 0x26, 0x5e, 0x6e, 0xb3, 0x80, 0x92, 0xa2, 0x42, 0x0e, 0x76, 0x3e, 0x8f, 0xa2, 0x00, 0x2c, + 0x54, 0x7c, 0xaf, 0xde, 0xf8, 0xf5, 0x8f, 0x99, 0xaf, 0x06, 0xf1, 0x9f, 0xfc, 0xc1, 0x03, 0xd9, + 0x8a, 0xaa, 0xc4, 0xd8, 0x83, 0x92, 0xaf, 0x51, 0xd9, 0xf4, 0x2e, 0x40, 0xd8, 0xf1, 0xa2, 0xd0, + /* bank # 46 */ + 0xde, 0xb6, 0x9e, 0xfc, 0xc0, 0x09, 0xdb, 0xfc, 0xc1, 0x0a, 0xd9, 0xb8, 0xae, 0xde, 0xba, 0xae, + 0xde, 0xfa, 0xb7, 0xbb, 0xf4, 0x2e, 0x40, 0xd8, 0xf1, 0xb8, 0xae, 0xde, 0xf8, 0xba, 0xae, 0xdf, + 0xf3, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xb0, 0xb4, 0xbb, 0xaf, 0xfb, 0xda, 0xb8, 0xa4, 0xd0, + 0x8d, 0x94, 0x1d, 0xf1, 0xe2, 0xd8, 0xf1, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xb3, 0xb7, 0xbb, + 0xd8, 0xf1, 0x8a, 0x92, 0xaf, 0x19, 0xd9, 0xf4, 0x2e, 0x84, 0xd8, 0xf3, 0xbc, 0xbc, 0xb1, 0x8b, + 0xc3, 0xbc, 0xbc, 0xb3, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x2e, 0x72, 0xd8, 0xf1, 0x8e, 0x91, 0x41, + 0xd9, 0xf4, 0x2e, 0x72, 0xd8, 0xf1, 0x89, 0x93, 0xa3, 0xc6, 0x60, 0x81, 0xa2, 0xd0, 0xc7, 0xf4, + 0x2e, 0xff, 0xd8, 0xf1, 0xa3, 0xde, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0x8b, 0xaa, + 0xc6, 0xf4, 0x2e, 0xff, 0xd8, 0xf1, 0x81, 0xaa, 0xc6, 0x9a, 0x60, 0x60, 0xb1, 0x81, 0xb5, 0x93, + 0xaf, 0x59, 0xb3, 0xb7, 0xd1, 0xd9, 0xf4, 0x2e, 0xff, 0xd8, 0xf1, 0x8a, 0x92, 0xaf, 0x21, 0xda, + 0xa3, 0xf8, 0xad, 0xde, 0xd8, 0x81, 0xaa, 0xc5, 0x85, 0x91, 0xaf, 0x21, 0xd9, 0xf4, 0x2e, 0xda, + 0xd8, 0xf1, 0xa1, 0xdf, 0xa2, 0xdf, 0xdf, 0x81, 0x95, 0xa5, 0xc7, 0x68, 0x89, 0x93, 0xa3, 0xc6, + 0x60, 0xad, 0xf8, 0xaf, 0xde, 0xf8, 0xf5, 0x89, 0x9f, 0x06, 0xf1, 0xfc, 0xc1, 0x03, 0xdb, 0x8d, + 0x9d, 0xaf, 0x21, 0xa3, 0xde, 0xf8, 0xd8, 0xf4, 0x2e, 0xff, 0xd8, 0xf1, 0x81, 0xa5, 0xc5, 0x92, + 0xaf, 0x49, 0xda, 0xa3, 0xf8, 0xf8, 0xd8, 0x91, 0xaf, 0x49, 0xda, 0xa3, 0xf8, 0xf8, 0xf8, 0xf8, + 0xd8, 0xf1, 0xa3, 0xf8, 0xf9, 0xd1, 0xd9, 0xb1, 0x83, 0xb9, 0xa1, 0xd0, 0xc6, 0xb3, 0xbb, 0xd8, + /* bank # 47 */ + 0xf5, 0x83, 0x9a, 0xaf, 0x1a, 0xf1, 0xbe, 0xb8, 0xae, 0xc1, 0x89, 0xb5, 0x9e, 0x74, 0xfd, 0x3f, + 0xbc, 0xbc, 0xb1, 0x8b, 0x34, 0xb7, 0x9f, 0xfc, 0xc0, 0x00, 0xbc, 0xbc, 0xbc, 0xb0, 0xbd, 0xb4, + 0xd9, 0xf4, 0x2f, 0x59, 0xd8, 0xf1, 0xa6, 0xf8, 0x86, 0x96, 0xae, 0x11, 0xd9, 0xa6, 0xdf, 0x88, + 0xbe, 0xbb, 0xa9, 0xd0, 0xc4, 0xf2, 0xa1, 0xd0, 0xc6, 0xa2, 0xd0, 0xc6, 0xbe, 0xbe, 0xbe, 0xdb, + 0xf1, 0x9e, 0xfc, 0xc3, 0x01, 0xd9, 0xf2, 0xbe, 0xa1, 0xd0, 0xf8, 0xf8, 0xf8, 0xa2, 0xd0, 0xf8, + 0xf8, 0xf8, 0xbe, 0xbe, 0xbe, 0xd8, 0xf4, 0x2f, 0x97, 0xd8, 0xf1, 0x9e, 0xfc, 0xc3, 0x01, 0xd9, + 0xf5, 0x8e, 0xae, 0x32, 0xf1, 0xdb, 0xfc, 0xc0, 0x01, 0x88, 0xbe, 0xbb, 0xa9, 0xd0, 0xc4, 0xf2, + 0xa1, 0xd0, 0xc6, 0xa2, 0xd0, 0xc6, 0xbe, 0xbe, 0xbe, 0xf4, 0x2f, 0x97, 0xd8, 0xf1, 0xa6, 0xfa, + 0x86, 0x96, 0xae, 0x39, 0xd9, 0xa6, 0xde, 0x87, 0xbe, 0xbb, 0xa9, 0xd0, 0xc4, 0xf2, 0xa1, 0xd0, + 0xc6, 0xa2, 0xd0, 0xc6, 0xbe, 0xbe, 0xbe, 0xd8, 0xf1, 0xbc, 0xbc, 0xbc, 0xb3, 0xbd, 0xbd, 0xbd, + 0xb7, 0xbe, 0xbe, 0xbe, 0xbb, 0xa5, 0xf8, 0xf9, 0xd1, 0xda, 0x86, 0xa7, 0xc3, 0xc5, 0xc7, 0xa5, + 0xde, 0x85, 0xa5, 0xd0, 0xc6, 0xd8, 0x85, 0x95, 0xaf, 0x71, 0xda, 0xf4, 0x2f, 0xd7, 0xd8, 0xf1, + 0x89, 0x93, 0xa3, 0x60, 0xf3, 0xbe, 0xbe, 0xaf, 0xf8, 0xf9, 0xd1, 0xda, 0xf3, 0xe2, 0xd8, 0xf1, + 0xbe, 0xbe, 0x86, 0xa7, 0xc3, 0xc5, 0xc7, 0xd8, 0xf1, 0xaf, 0xdf, 0xf9, 0x89, 0x9f, 0x2d, 0x83, + 0x0d, 0xf5, 0x99, 0xaf, 0x1a, 0x8f, 0x7e, 0x9f, 0xa8, 0x12, 0x99, 0x2e, 0xf1, 0xdf, 0xdf, 0xaf, + 0xdf, 0xf9, 0x89, 0x9f, 0x4d, 0x83, 0x0d, 0xf5, 0x9b, 0xaf, 0x02, 0x8f, 0x66, 0xf1, 0x9f, 0xfc, + /* bank # 48 */ + 0xc0, 0x03, 0xd9, 0xf5, 0xa8, 0xd0, 0x12, 0x99, 0x36, 0xd8, 0xf1, 0x88, 0x98, 0xa6, 0x10, 0xa7, + 0x38, 0x86, 0x9f, 0xaf, 0xde, 0x00, 0xfd, 0x08, 0x87, 0x00, 0x8f, 0xf3, 0xae, 0xc0, 0xf1, 0xbc, + 0xbc, 0xb1, 0x82, 0xc3, 0xbc, 0xbc, 0xd8, 0xf3, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xbb, 0xb3, + 0xb7, 0xa2, 0xf8, 0xf2, 0xf8, 0xf1, 0x80, 0x9d, 0xad, 0xd0, 0x7c, 0xf2, 0xa2, 0xfa, 0xf9, 0xd1, + 0xf1, 0xb9, 0xac, 0xd9, 0xde, 0xda, 0xf8, 0xd8, 0xf5, 0xbe, 0xbe, 0xba, 0xa7, 0x85, 0x95, 0x78, + 0x8e, 0x9e, 0x7c, 0xbc, 0xbc, 0xbd, 0xbd, 0xb2, 0xb6, 0xf1, 0xa9, 0x89, 0x99, 0x62, 0xf0, 0x97, + 0x40, 0x99, 0x6c, 0x97, 0x48, 0xb9, 0xb1, 0xb5, 0xf1, 0xaf, 0x80, 0x91, 0x28, 0x8c, 0x9f, 0x00, + 0x83, 0x65, 0xd9, 0xf4, 0x30, 0x89, 0xd8, 0xf1, 0x9d, 0xfc, 0xc3, 0x04, 0xaf, 0xb2, 0x89, 0xd9, + 0xc3, 0xc1, 0xda, 0xc1, 0xc3, 0xd8, 0xf4, 0x75, 0x4a, 0xd8, 0xf2, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, + 0xbd, 0xb9, 0xb3, 0xb7, 0xa6, 0x81, 0x92, 0x49, 0xf9, 0xdb, 0xf1, 0xb1, 0x8c, 0xb5, 0x9c, 0x21, + 0xd9, 0xf5, 0xb3, 0x85, 0xb7, 0x95, 0x78, 0x8e, 0x9e, 0x7c, 0xf1, 0xb1, 0x8d, 0xb5, 0x9d, 0xad, + 0x1a, 0xf0, 0x96, 0x40, 0x9d, 0x3c, 0x96, 0x48, 0xd8, 0xf1, 0xb1, 0x81, 0xb5, 0x9d, 0xb9, 0xa6, + 0x0a, 0x8d, 0x96, 0x05, 0xd9, 0xf4, 0x30, 0xf0, 0xd8, 0xf2, 0xb3, 0x81, 0xb7, 0x92, 0xbb, 0xaf, + 0x49, 0xf9, 0xf9, 0xdb, 0xf1, 0xb1, 0x8c, 0xb5, 0x9c, 0xb9, 0xa6, 0x21, 0xf4, 0x30, 0xf0, 0xd8, + 0xf1, 0xb3, 0x8e, 0xbb, 0xa8, 0xd0, 0xc4, 0xc7, 0xf3, 0xb9, 0xac, 0xd0, 0xde, 0xf4, 0x31, 0x01, + 0xd8, 0xf1, 0xb3, 0x85, 0xbb, 0xa8, 0xd0, 0xc4, 0xc7, 0xf3, 0xb9, 0xac, 0xd0, 0xde, 0xf8, 0xdf, + /* bank # 49 */ + 0xf8, 0xd8, 0xf3, 0xb5, 0x9c, 0xfc, 0xc3, 0x04, 0xdb, 0xfc, 0xc2, 0x00, 0xd9, 0xf2, 0xac, 0xd0, + 0xde, 0xd8, 0xf2, 0xbb, 0xaf, 0xb7, 0x92, 0xb3, 0x82, 0x19, 0xdb, 0xa2, 0xdf, 0xa1, 0xd0, 0xc4, + 0xac, 0xd0, 0xc5, 0xf3, 0xa7, 0xd0, 0xdf, 0xf1, 0xb9, 0xaa, 0xde, 0xa1, 0xdf, 0xb5, 0x9b, 0xfc, + 0xc1, 0x00, 0xb8, 0xbe, 0xa7, 0xd0, 0xde, 0xbe, 0xbe, 0xbe, 0xd8, 0xf1, 0xbb, 0xaf, 0x89, 0xb7, + 0x98, 0x19, 0xa9, 0x80, 0xd9, 0x38, 0xd8, 0xaf, 0x89, 0x39, 0xa9, 0x80, 0xda, 0x3c, 0xd8, 0xa1, + 0xf8, 0xf9, 0xd1, 0xda, 0xf9, 0xdf, 0xf8, 0xf4, 0x75, 0x32, 0xf1, 0xff, 0xd8, 0xaf, 0x2e, 0x88, + 0xf5, 0x75, 0xda, 0xff, 0xd8, 0x71, 0xda, 0xf1, 0xff, 0xd8, 0x82, 0xa7, 0xf3, 0xc1, 0xf2, 0x80, + 0xc2, 0xf1, 0x97, 0x86, 0x49, 0x2e, 0xa6, 0xd0, 0x50, 0x96, 0x86, 0xaf, 0x75, 0xd9, 0x88, 0xa2, + 0xd0, 0xf3, 0xc0, 0xc3, 0xf1, 0xda, 0x8f, 0x96, 0xa2, 0xd0, 0xf3, 0xc2, 0xc3, 0x82, 0xb6, 0x9b, + 0x70, 0x70, 0xf1, 0xd8, 0xb7, 0xaf, 0xdf, 0xf9, 0x89, 0x99, 0xaf, 0x10, 0x80, 0x9f, 0x21, 0xda, + 0x2e, 0xd8, 0x89, 0x99, 0xaf, 0x31, 0xda, 0xdf, 0xd8, 0xaf, 0x82, 0x92, 0xf3, 0x41, 0xd9, 0xf1, + 0xdf, 0xd8, 0xaf, 0x82, 0xf3, 0x19, 0xd9, 0xf1, 0xdf, 0xd8, 0xf1, 0x89, 0x90, 0xaf, 0xd0, 0x09, + 0x8f, 0x99, 0xaf, 0x51, 0xdb, 0x89, 0x31, 0xf3, 0x82, 0x92, 0x19, 0xf2, 0xb1, 0x8c, 0xb5, 0x9c, + 0x71, 0xd9, 0xf1, 0xdf, 0xf9, 0xf2, 0xb9, 0xac, 0xd0, 0xf8, 0xf8, 0xf3, 0xdf, 0xd8, 0xb3, 0xb7, + 0xbb, 0x82, 0xac, 0xf3, 0xc0, 0xa2, 0x80, 0x22, 0xf1, 0xa9, 0x22, 0x26, 0x9f, 0xaf, 0x29, 0xda, + 0xac, 0xde, 0xff, 0xd8, 0xa2, 0xf2, 0xde, 0xf1, 0xa9, 0xdf, 0xf2, 0x82, 0xb8, 0xbe, 0xa9, 0xc3, + /* bank # 50 */ + 0x81, 0xc5, 0xb0, 0xbc, 0xf1, 0xb5, 0x9b, 0xfc, 0xc1, 0x03, 0xb4, 0xbd, 0xd9, 0xf4, 0x32, 0x28, + 0xd8, 0xf2, 0x89, 0x99, 0xa9, 0x49, 0xda, 0xf4, 0x32, 0x28, 0xd8, 0xf1, 0x9a, 0xfc, 0xc0, 0x04, + 0xa7, 0xd0, 0xd9, 0x88, 0x97, 0x30, 0xda, 0xde, 0xd8, 0xf1, 0xbc, 0xb1, 0x80, 0xbb, 0xbe, 0xbe, + 0xbe, 0xaf, 0xc2, 0x8c, 0xc1, 0x81, 0xc3, 0x83, 0xc7, 0xbc, 0xbc, 0xb3, 0x8f, 0xb7, 0xbd, 0xbd, + 0xbd, 0x9f, 0xba, 0xa7, 0x61, 0xdb, 0x69, 0x71, 0xff, 0xd8, 0xf1, 0xbb, 0xad, 0xd0, 0xde, 0xf8, + 0xb1, 0x84, 0xb6, 0x96, 0xba, 0xa7, 0xd0, 0x7e, 0xb7, 0x96, 0xa7, 0x01, 0xb2, 0x87, 0x9d, 0x05, + 0xdb, 0xb3, 0x8d, 0xb6, 0x97, 0x79, 0xf3, 0xb1, 0x8c, 0x96, 0x49, 0xf1, 0xbb, 0xad, 0xd0, 0xf8, + 0xd8, 0xf3, 0xb9, 0xac, 0xd0, 0xf8, 0xf9, 0xd1, 0xd9, 0xf1, 0xbb, 0xad, 0xd0, 0xf8, 0xd8, 0xb3, + 0xb7, 0xbb, 0x97, 0x8c, 0xaf, 0xf3, 0x79, 0xd9, 0xf4, 0x32, 0x9b, 0xd8, 0xf1, 0xa1, 0x81, 0x9d, + 0x34, 0xaa, 0xd0, 0x8a, 0x50, 0xf4, 0x75, 0x32, 0xf4, 0x32, 0xbb, 0xd8, 0xf3, 0xa7, 0xd0, 0xfa, + 0xb5, 0x9c, 0xfc, 0xc2, 0x07, 0xd9, 0xf8, 0xd8, 0xb7, 0x97, 0x8c, 0xaf, 0x79, 0xda, 0xf1, 0x87, + 0x91, 0xa1, 0x6c, 0xaa, 0xd0, 0x9a, 0x70, 0xbb, 0xf4, 0x75, 0x32, 0xd8, 0xf1, 0x91, 0xfc, 0xc1, + 0x0a, 0xd9, 0xf4, 0x32, 0xfc, 0xd8, 0xf1, 0x81, 0xa1, 0xc2, 0xf9, 0xdf, 0xf8, 0x80, 0x9d, 0xba, + 0xa6, 0xd0, 0x38, 0xfd, 0x31, 0xbb, 0xaf, 0xde, 0xf3, 0x82, 0xce, 0xf1, 0x8f, 0x90, 0x08, 0xfd, + 0x0f, 0x8d, 0x9f, 0x65, 0xd9, 0xf4, 0x32, 0xfc, 0xd8, 0xf1, 0xaf, 0xde, 0xf2, 0x8c, 0xce, 0xf2, + 0x82, 0x9f, 0x25, 0xd9, 0xf1, 0xba, 0xa6, 0xd0, 0xde, 0xf3, 0x8d, 0xce, 0xd8, 0xf1, 0xb5, 0x9b, + /* bank # 51 */ + 0xfc, 0xc1, 0x03, 0xd9, 0xbc, 0xbd, 0xbe, 0xf4, 0x33, 0x30, 0xd8, 0xf1, 0xb8, 0xbe, 0xaa, 0xd0, + 0xde, 0xf2, 0xb3, 0x81, 0xb7, 0x92, 0xa9, 0x49, 0xd9, 0xbc, 0xbd, 0xf4, 0x33, 0x30, 0xd8, 0xf1, + 0xbc, 0xbd, 0xb0, 0xb4, 0x8d, 0x97, 0x31, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xd9, 0xaa, 0xd0, 0xf8, + 0xd8, 0xf1, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xb0, 0x84, 0xb8, 0xa5, 0xc3, 0xc5, 0xc7, 0x83, + 0xa4, 0xc3, 0xc5, 0xc7, 0xf0, 0xb2, 0x81, 0xb6, 0x91, 0xa3, 0x3c, 0x11, 0x0c, 0x58, 0x2c, 0x50, + 0xf1, 0xb0, 0x83, 0xb4, 0x93, 0xa3, 0x2c, 0x54, 0x7c, 0x92, 0x71, 0xf0, 0x95, 0xae, 0x2c, 0x50, + 0x78, 0x8e, 0xbe, 0xb9, 0xaa, 0xc2, 0xbc, 0xbd, 0xd8, 0xf2, 0xbb, 0xb3, 0xb7, 0x82, 0x91, 0xaf, + 0x31, 0xda, 0xf4, 0x33, 0xd4, 0xd8, 0xf1, 0x8d, 0xb7, 0x96, 0xbb, 0xa6, 0x40, 0xac, 0x8c, 0x9c, + 0x0c, 0x30, 0xba, 0x8d, 0x9d, 0xa7, 0x39, 0xdb, 0xf3, 0xb1, 0x8c, 0xb6, 0x96, 0x49, 0xd9, 0xf1, + 0x84, 0xb5, 0x94, 0xb9, 0xa4, 0xd0, 0x5e, 0xf0, 0xb7, 0x9d, 0x38, 0xd8, 0xf1, 0xb3, 0x8d, 0xba, + 0xa7, 0xc6, 0xb5, 0x9c, 0xfc, 0xc2, 0x04, 0xd9, 0xb1, 0x81, 0xb6, 0x97, 0xa7, 0x25, 0x8b, 0x6e, + 0x81, 0xb9, 0xa1, 0x34, 0xda, 0xb2, 0x87, 0xb6, 0x97, 0x00, 0xfd, 0x3e, 0xb1, 0x81, 0x25, 0x8b, + 0x4e, 0x81, 0xb9, 0xa1, 0x34, 0xd8, 0xf1, 0xbb, 0xaa, 0xd0, 0xdf, 0xac, 0xde, 0xd0, 0xde, 0xad, + 0xd0, 0xdf, 0xf1, 0xff, 0xd8, 0xf2, 0xb3, 0xb7, 0xaf, 0x82, 0x9c, 0x39, 0xdb, 0xf1, 0x86, 0x90, + 0x09, 0xaa, 0xd0, 0x8a, 0x9d, 0xd9, 0x74, 0xf4, 0x33, 0xef, 0xda, 0xf1, 0xaa, 0xd0, 0xdf, 0xd8, + 0xf3, 0xb9, 0xac, 0xd0, 0xf8, 0xf9, 0xd1, 0xd9, 0xf2, 0xbb, 0xa2, 0xfa, 0xf8, 0xda, 0xf2, 0xbb, + /* bank # 52 */ + 0xa2, 0xfa, 0xd8, 0xf2, 0xb3, 0x82, 0xb6, 0x9b, 0xbb, 0xaf, 0x31, 0xdb, 0xf1, 0x89, 0xb5, 0x9a, + 0x61, 0xd9, 0xf2, 0xa1, 0xd0, 0xf8, 0xf8, 0xd8, 0xf2, 0x82, 0xaf, 0xc4, 0xf8, 0xf8, 0xf8, 0xf8, + 0x8f, 0xb7, 0x91, 0x15, 0xda, 0xa1, 0xd0, 0xc0, 0xd8, 0x82, 0xaf, 0xc2, 0xf9, 0xd1, 0xd9, 0xf1, + 0xb9, 0xac, 0xde, 0xad, 0xde, 0xdf, 0xb9, 0xa1, 0xdf, 0xbb, 0xad, 0xd0, 0xdf, 0xd8, 0xf2, 0x82, + 0x91, 0xaf, 0x31, 0xda, 0xf1, 0xb1, 0x81, 0x9d, 0xb9, 0xa1, 0x3c, 0xd8, 0xf2, 0xb3, 0xbb, 0x82, + 0x91, 0xaf, 0x31, 0xd1, 0xd9, 0xf1, 0xb1, 0x81, 0xb5, 0x9b, 0xb9, 0xa1, 0x3e, 0xd8, 0xf1, 0xb3, + 0x8c, 0xb7, 0x9c, 0xbb, 0xac, 0xd0, 0x10, 0xac, 0xde, 0xad, 0xd0, 0xdf, 0x92, 0x82, 0xaf, 0xf1, + 0xca, 0xf2, 0x91, 0x35, 0xf1, 0x96, 0x8f, 0xa6, 0xd9, 0x00, 0xdb, 0xaf, 0x8a, 0x90, 0x6d, 0xd9, + 0xa6, 0x8f, 0x96, 0x01, 0x8a, 0x60, 0xaa, 0xd0, 0xdf, 0xf2, 0x81, 0xac, 0xd0, 0xc5, 0xd8, 0xf1, + 0xff, 0xd8, 0xf0, 0xb9, 0xb1, 0xb6, 0xaf, 0x8d, 0x92, 0x4c, 0x71, 0x54, 0x68, 0x5c, 0x60, 0x44, + 0x79, 0xe0, 0xd8, 0xf1, 0xba, 0xb1, 0xa4, 0x8f, 0xc0, 0xc3, 0xc5, 0xc7, 0xb9, 0xb5, 0xf1, 0xaa, + 0x82, 0x90, 0x25, 0xf3, 0xad, 0xdf, 0xd9, 0xf8, 0xf8, 0xd8, 0xf1, 0xa1, 0x81, 0x91, 0xf0, 0x34, + 0x82, 0x38, 0xf1, 0xaa, 0x2d, 0xf5, 0x8a, 0x90, 0x30, 0xd9, 0xf3, 0xad, 0xfa, 0xd8, 0xf0, 0xaa, + 0x8f, 0x9f, 0x04, 0x28, 0x51, 0x79, 0x1d, 0x30, 0x14, 0x38, 0xbc, 0xbc, 0xbc, 0xa2, 0xd0, 0x8a, + 0x9a, 0x2c, 0x50, 0x50, 0x78, 0x78, 0xbc, 0x82, 0x90, 0xaa, 0xf5, 0x7c, 0xf3, 0xd9, 0xad, 0xfa, + 0xd8, 0xf1, 0xb8, 0xae, 0x82, 0xc6, 0xb9, 0xa1, 0x81, 0x90, 0x0a, 0x81, 0x92, 0x18, 0xa2, 0xd0, + /* bank # 53 */ + 0x81, 0xc1, 0xf3, 0xad, 0xfb, 0xf9, 0xf1, 0xda, 0xa2, 0xd0, 0xdf, 0xd8, 0xa2, 0xd0, 0xfa, 0xf9, + 0xd1, 0xda, 0xaa, 0x82, 0x9d, 0x7e, 0x76, 0xad, 0x8a, 0xd0, 0x31, 0x5c, 0xf0, 0xaa, 0x8d, 0x9d, + 0x54, 0x78, 0xfd, 0x7f, 0xf1, 0x8a, 0x92, 0x55, 0x9d, 0xad, 0xd0, 0x72, 0x7e, 0xd8, 0xf4, 0x74, + 0x91, 0xe0, 0xd8, 0xf1, 0xb1, 0xb9, 0x82, 0xa2, 0xd0, 0xc2, 0xf2, 0xa3, 0xfa, 0xf3, 0xb8, 0xa7, + 0xf8, 0xf9, 0xd1, 0xda, 0xf2, 0xe2, 0xd8, 0xbb, 0xb3, 0xe0, 0xf1, 0xb1, 0xaf, 0x8f, 0x9f, 0x31, + 0x85, 0xa5, 0xd0, 0xda, 0xc6, 0xf4, 0x35, 0x67, 0xd8, 0xf1, 0xf8, 0xf9, 0xd1, 0xd9, 0xc6, 0xf5, + 0xad, 0xd0, 0x8d, 0x9e, 0x7f, 0xda, 0xf9, 0xd8, 0xf1, 0xe0, 0xf1, 0xb6, 0x97, 0xa7, 0x66, 0xb7, + 0x93, 0xf0, 0x71, 0x71, 0x60, 0xe0, 0xf0, 0x01, 0x29, 0x51, 0x79, 0xe0, 0xf1, 0xc2, 0xc5, 0xc7, + 0xb2, 0x87, 0xb6, 0x97, 0x2c, 0xfd, 0x01, 0xe0, 0xf1, 0xc2, 0xc5, 0xc7, 0xb2, 0x87, 0xc1, 0xe0, + 0xf1, 0xb2, 0x81, 0x97, 0x66, 0xe0, 0xf0, 0x38, 0x10, 0x28, 0x40, 0x88, 0xe0, 0xf0, 0x24, 0x70, + 0x59, 0x44, 0x69, 0x38, 0x64, 0x48, 0x31, 0x2d, 0x51, 0x79, 0xe0, 0xf0, 0x24, 0x58, 0x3d, 0x40, + 0x34, 0x49, 0x2d, 0x51, 0xe0, 0xf1, 0x87, 0xa1, 0x00, 0x2c, 0x54, 0x7c, 0xf0, 0x81, 0xa7, 0x04, + 0x28, 0x50, 0x78, 0xfd, 0x7f, 0xf1, 0xa7, 0x87, 0x96, 0x59, 0x91, 0xa1, 0x02, 0x0e, 0x16, 0x1e, + 0xe0, 0xd8, 0xf0, 0xbe, 0xbe, 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xb3, 0xbb, 0x8c, 0xac, + 0xf4, 0x78, 0x4e, 0x8d, 0xad, 0xf4, 0x78, 0x4e, 0x8e, 0xae, 0xf4, 0x78, 0x4e, 0xbc, 0xb0, 0x80, + 0xba, 0xaf, 0xf1, 0xde, 0xdf, 0xdf, 0xd0, 0xf2, 0xc2, 0xcb, 0xc5, 0xbc, 0xbc, 0xbc, 0xb2, 0x8f, + /* bank # 54 */ + 0xd0, 0xbd, 0xb5, 0x9e, 0xf1, 0x02, 0xfd, 0x03, 0x26, 0xfd, 0x03, 0x46, 0xfd, 0x03, 0xbd, 0xbd, + 0xbd, 0xb5, 0x90, 0xbb, 0xaf, 0x02, 0xf0, 0x28, 0x50, 0xf1, 0x1e, 0x91, 0xf0, 0x20, 0x48, 0xf1, + 0x16, 0xf0, 0x38, 0x92, 0x40, 0xb3, 0xb7, 0x8f, 0xf2, 0xac, 0xc0, 0xad, 0xc2, 0xae, 0xc4, 0xf1, + 0xa9, 0xfa, 0xf9, 0xd1, 0xd9, 0xf4, 0x36, 0x3f, 0xd8, 0xf1, 0xa9, 0xfa, 0xf4, 0x38, 0x11, 0xd8, + 0xf0, 0xb7, 0x8c, 0x9c, 0xba, 0xf4, 0x78, 0x1d, 0xf1, 0xc1, 0xb3, 0x8d, 0x9d, 0xba, 0xf4, 0x78, + 0x1d, 0xf1, 0x1c, 0xb3, 0x8e, 0x9e, 0xba, 0xf4, 0x78, 0x1d, 0xf1, 0x1c, 0xb3, 0x8f, 0xd7, 0xfd, + 0x3e, 0xf2, 0x8d, 0xc1, 0x8e, 0xc1, 0xf1, 0x8f, 0xd5, 0xfd, 0x30, 0xd4, 0xd0, 0xfd, 0x70, 0xf1, + 0xd0, 0x2a, 0xd2, 0xf0, 0x00, 0xd2, 0xa9, 0xde, 0x8f, 0xb5, 0x97, 0xaf, 0xf5, 0x40, 0xd9, 0xf2, + 0xa9, 0xf8, 0xd8, 0x97, 0xaf, 0xf5, 0x48, 0xd9, 0xf3, 0xa9, 0xf8, 0xd8, 0xf2, 0xaf, 0xde, 0xf8, + 0xd4, 0xfd, 0x0c, 0xb7, 0x8f, 0x9d, 0x05, 0xda, 0xf4, 0x36, 0xb8, 0xd8, 0xf2, 0xb5, 0x97, 0xde, + 0xf8, 0xd0, 0x37, 0xfd, 0x0e, 0x3f, 0xfd, 0x0e, 0x8d, 0xb7, 0x9f, 0xd0, 0x05, 0xd9, 0xa9, 0xf8, + 0xd8, 0xaf, 0x0d, 0xd9, 0xa9, 0xf3, 0xf8, 0xd8, 0xd8, 0xf2, 0xaf, 0xde, 0xf8, 0xd4, 0xfd, 0x0c, + 0x8f, 0x9e, 0x05, 0xda, 0xf4, 0x36, 0xe3, 0xd8, 0xf2, 0xb5, 0x97, 0xde, 0xf8, 0xd0, 0x37, 0xfd, + 0x0e, 0x3f, 0xfd, 0x0e, 0x8e, 0xb7, 0x9f, 0xd0, 0x05, 0xd9, 0xa9, 0xf8, 0xd8, 0xaf, 0x0d, 0xd9, + 0xa9, 0xf3, 0xf8, 0xd8, 0xf1, 0x8c, 0xaf, 0xde, 0xf2, 0xc0, 0x8f, 0xf0, 0xd4, 0xfd, 0x30, 0x9f, + 0xf5, 0x00, 0xb1, 0x88, 0x04, 0xd9, 0xa9, 0xf2, 0xf8, 0xd8, 0xf5, 0xaf, 0x24, 0xd9, 0xa9, 0xf3, + /* bank # 55 */ + 0xf8, 0xd8, 0xf0, 0xaf, 0xb3, 0x89, 0xc4, 0xc7, 0x8f, 0xd0, 0xd4, 0xfd, 0x40, 0xd5, 0xfd, 0x40, + 0xb1, 0x88, 0xd0, 0xf5, 0x44, 0xd9, 0xa9, 0xf2, 0xf8, 0xd8, 0xaf, 0xf5, 0x6c, 0xd9, 0xa9, 0xf3, + 0xf8, 0xd8, 0xb3, 0x8f, 0xb5, 0x99, 0xf5, 0xaf, 0x60, 0xd9, 0xaa, 0xf8, 0xf4, 0x37, 0x3a, 0xd8, + 0xf1, 0xb1, 0x8a, 0xb7, 0x9f, 0xaf, 0x59, 0xd9, 0xaa, 0xde, 0xd8, 0xf5, 0xb3, 0x8f, 0xb5, 0x99, + 0xaf, 0x68, 0xd9, 0xaa, 0xfa, 0xda, 0xaa, 0xdf, 0xd8, 0xf1, 0x8a, 0xaf, 0xd4, 0xfd, 0x00, 0xd5, + 0xfd, 0x40, 0x8f, 0xd0, 0xf5, 0x14, 0xa9, 0xd0, 0xd9, 0xde, 0xda, 0xf8, 0xd8, 0xaf, 0x3c, 0xa9, + 0xd0, 0xd9, 0xdf, 0xda, 0xfa, 0xd8, 0xf1, 0x8a, 0xaf, 0xd6, 0xfd, 0x00, 0xd7, 0xfd, 0x40, 0x8f, + 0x9a, 0xd0, 0xf5, 0x04, 0xa9, 0xd9, 0xf2, 0xf8, 0xd8, 0xaf, 0xf5, 0x2c, 0xa9, 0xd9, 0xf3, 0xf8, + 0xd8, 0x8c, 0xaf, 0xf2, 0xc0, 0xf1, 0x8f, 0xd4, 0xfd, 0x30, 0xb7, 0x9f, 0x02, 0xfd, 0x1e, 0xd0, + 0x10, 0xaf, 0xde, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xbd, 0xbd, 0xbd, 0x93, 0xf5, 0x02, 0xf1, + 0xbd, 0xf8, 0xf9, 0xd1, 0xda, 0xf4, 0x37, 0xb2, 0xd8, 0xf1, 0xb1, 0x8a, 0x9f, 0x59, 0xda, 0xf4, + 0x37, 0xc8, 0xd8, 0xf1, 0xb1, 0x8b, 0x9f, 0xaf, 0x51, 0xda, 0xf4, 0x37, 0xc8, 0xd8, 0xf1, 0xb5, + 0x9b, 0xb3, 0x8f, 0x41, 0xd9, 0xa9, 0xf2, 0xf8, 0xd8, 0xf1, 0xaf, 0xb7, 0x9f, 0xb1, 0x8a, 0x79, + 0xda, 0xf4, 0x37, 0xe7, 0xd8, 0xf1, 0x8b, 0x71, 0xda, 0xf4, 0x37, 0xe7, 0xd8, 0xf1, 0xb5, 0x9b, + 0xb3, 0x8f, 0x49, 0xd9, 0xa9, 0xf3, 0xf8, 0xd8, 0xf0, 0xa9, 0xf2, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, + 0xf9, 0xf9, 0xaa, 0xd0, 0xf0, 0xda, 0xde, 0xf5, 0xe2, 0xf0, 0xd9, 0xf8, 0xd8, 0xa9, 0xf3, 0xf9, + /* bank # 56 */ + 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xaa, 0xd0, 0xf0, 0xda, 0xdf, 0xf6, 0xe2, 0xf0, 0xd9, 0xfa, + 0xd8, 0xd8, 0xf0, 0xbc, 0xb0, 0x80, 0xbd, 0xb4, 0x90, 0xbe, 0xb8, 0xa0, 0xe0, 0xf0, 0xaf, 0xf2, + 0x11, 0x3d, 0xf3, 0x15, 0x3d, 0xf2, 0xb2, 0x8f, 0xd0, 0xcd, 0xcf, 0xf3, 0xdf, 0xdf, 0xdf, 0xdf, + 0xf1, 0xd4, 0xfd, 0x70, 0xd5, 0xfd, 0x70, 0xd6, 0xfd, 0x70, 0xd7, 0xfd, 0x70, 0xb6, 0x9f, 0x0c, + 0x10, 0x18, 0xf5, 0x00, 0xb5, 0x96, 0xf5, 0x18, 0xbb, 0xaf, 0xd0, 0xb7, 0x9f, 0xe0, 0xf0, 0xd0, + 0xf3, 0xcf, 0xf2, 0xcc, 0xd0, 0xf3, 0xcd, 0xf2, 0xca, 0xd0, 0xf3, 0xcb, 0xf2, 0xc8, 0xd0, 0xf3, + 0xc9, 0xe0 diff --git a/src/util/ICM_20948_C.c b/src/util/ICM_20948_C.c new file mode 100644 index 0000000..eaa7826 --- /dev/null +++ b/src/util/ICM_20948_C.c @@ -0,0 +1,2597 @@ +#include "ICM_20948_C.h" +#include "ICM_20948_REGISTERS.h" +#include "AK09916_REGISTERS.h" + +/* + * Icm20948 device require a DMP image to be loaded on init + * Provide such images by mean of a byte array +*/ +#if defined(ICM_20948_USE_DMP) // Only include the 14301 Bytes of DMP if ICM_20948_USE_DMP is defined + +#if defined(ARDUINO_ARCH_MBED) // ARDUINO_ARCH_MBED (APOLLO3 v2) does not support or require pgmspace.h / PROGMEM +const uint8_t dmp3_image[] = { +#elif (defined(__AVR__) || defined(__arm__) || defined(__ARDUINO_ARC__) || defined(ESP8266)) && !defined(__linux__) // Store the DMP firmware in PROGMEM on older AVR (ATmega) platforms +#define ICM_20948_USE_PROGMEM_FOR_DMP +#include +const uint8_t dmp3_image[] PROGMEM = { +#else +const uint8_t dmp3_image[] = { +#endif + +#include "icm20948_img.dmp3a.h" +}; +#endif + +// ICM-20948 data is big-endian. We need to make it little-endian when writing into icm_20948_DMP_data_t +const int DMP_Quat9_Byte_Ordering[icm_20948_DMP_Quat9_Bytes] = + { + 3, 2, 1, 0, 7, 6, 5, 4, 11, 10, 9, 8, 13, 12 // Also used for Geomag +}; +const int DMP_Quat6_Byte_Ordering[icm_20948_DMP_Quat6_Bytes] = + { + 3, 2, 1, 0, 7, 6, 5, 4, 11, 10, 9, 8 // Also used for Gyro_Calibr, Compass_Calibr +}; +const int DMP_PQuat6_Byte_Ordering[icm_20948_DMP_PQuat6_Bytes] = + { + 1, 0, 3, 2, 5, 4 // Also used for Raw_Accel, Compass +}; +const int DMP_Raw_Gyro_Byte_Ordering[icm_20948_DMP_Raw_Gyro_Bytes + icm_20948_DMP_Gyro_Bias_Bytes] = + { + 1, 0, 3, 2, 5, 4, 7, 6, 9, 8, 11, 10}; +const int DMP_Activity_Recognition_Byte_Ordering[icm_20948_DMP_Activity_Recognition_Bytes] = + { + 0, 1, 5, 4, 3, 2}; +const int DMP_Secondary_On_Off_Byte_Ordering[icm_20948_DMP_Secondary_On_Off_Bytes] = + { + 1, 0}; + +const uint16_t inv_androidSensor_to_control_bits[ANDROID_SENSOR_NUM_MAX] = + { + // Data output control 1 register bit definition + // 16-bit accel 0x8000 + // 16-bit gyro 0x4000 + // 16-bit compass 0x2000 + // 16-bit ALS 0x1000 + // 32-bit 6-axis quaternion 0x0800 + // 32-bit 9-axis quaternion + heading accuracy 0x0400 + // 16-bit pedometer quaternion 0x0200 + // 32-bit Geomag rv + heading accuracy 0x0100 + // 16-bit Pressure 0x0080 + // 32-bit calibrated gyro 0x0040 + // 32-bit calibrated compass 0x0020 + // Pedometer Step Detector 0x0010 + // Header 2 0x0008 + // Pedometer Step Indicator Bit 2 0x0004 + // Pedometer Step Indicator Bit 1 0x0002 + // Pedometer Step Indicator Bit 0 0x0001 + // Unsupported Sensors are 0xFFFF + + 0xFFFF, // 0 Meta Data + 0x8008, // 1 Accelerometer + 0x0028, // 2 Magnetic Field + 0x0408, // 3 Orientation + 0x4048, // 4 Gyroscope + 0x1008, // 5 Light + 0x0088, // 6 Pressure + 0xFFFF, // 7 Temperature + 0xFFFF, // 8 Proximity <----------- fixme + 0x0808, // 9 Gravity + 0x8808, // 10 Linear Acceleration + 0x0408, // 11 Rotation Vector + 0xFFFF, // 12 Humidity + 0xFFFF, // 13 Ambient Temperature + 0x2008, // 14 Magnetic Field Uncalibrated + 0x0808, // 15 Game Rotation Vector + 0x4008, // 16 Gyroscope Uncalibrated + 0x0000, // 17 Significant Motion + 0x0018, // 18 Step Detector + 0x0010, // 19 Step Counter <----------- fixme + 0x0108, // 20 Geomagnetic Rotation Vector + 0xFFFF, // 21 ANDROID_SENSOR_HEART_RATE, + 0xFFFF, // 22 ANDROID_SENSOR_PROXIMITY, + + 0x8008, // 23 ANDROID_SENSOR_WAKEUP_ACCELEROMETER, + 0x0028, // 24 ANDROID_SENSOR_WAKEUP_MAGNETIC_FIELD, + 0x0408, // 25 ANDROID_SENSOR_WAKEUP_ORIENTATION, + 0x4048, // 26 ANDROID_SENSOR_WAKEUP_GYROSCOPE, + 0x1008, // 27 ANDROID_SENSOR_WAKEUP_LIGHT, + 0x0088, // 28 ANDROID_SENSOR_WAKEUP_PRESSURE, + 0x0808, // 29 ANDROID_SENSOR_WAKEUP_GRAVITY, + 0x8808, // 30 ANDROID_SENSOR_WAKEUP_LINEAR_ACCELERATION, + 0x0408, // 31 ANDROID_SENSOR_WAKEUP_ROTATION_VECTOR, + 0xFFFF, // 32 ANDROID_SENSOR_WAKEUP_RELATIVE_HUMIDITY, + 0xFFFF, // 33 ANDROID_SENSOR_WAKEUP_AMBIENT_TEMPERATURE, + 0x2008, // 34 ANDROID_SENSOR_WAKEUP_MAGNETIC_FIELD_UNCALIBRATED, + 0x0808, // 35 ANDROID_SENSOR_WAKEUP_GAME_ROTATION_VECTOR, + 0x4008, // 36 ANDROID_SENSOR_WAKEUP_GYROSCOPE_UNCALIBRATED, + 0x0018, // 37 ANDROID_SENSOR_WAKEUP_STEP_DETECTOR, + 0x0010, // 38 ANDROID_SENSOR_WAKEUP_STEP_COUNTER, + 0x0108, // 39 ANDROID_SENSOR_WAKEUP_GEOMAGNETIC_ROTATION_VECTOR + 0xFFFF, // 40 ANDROID_SENSOR_WAKEUP_HEART_RATE, + 0x0000, // 41 ANDROID_SENSOR_WAKEUP_TILT_DETECTOR, + 0x8008, // 42 Raw Acc + 0x4048, // 43 Raw Gyr +}; + +const ICM_20948_Serif_t NullSerif = { + NULL, // write + NULL, // read + NULL, // user +}; + +// Private function prototypes + +// Function definitions +ICM_20948_Status_e ICM_20948_init_struct(ICM_20948_Device_t *pdev) +{ + // Initialize all elements by 0 except for _last_bank + // Initialize _last_bank to 4 (invalid bank number) + // so ICM_20948_set_bank function does not skip issuing bank change operation + static const ICM_20948_Device_t init_device = { ._last_bank = 4 }; + *pdev = init_device; + return ICM_20948_Stat_Ok; +} + +ICM_20948_Status_e ICM_20948_link_serif(ICM_20948_Device_t *pdev, const ICM_20948_Serif_t *s) +{ + if (s == NULL) + { + return ICM_20948_Stat_ParamErr; + } + if (pdev == NULL) + { + return ICM_20948_Stat_ParamErr; + } + pdev->_serif = s; + return ICM_20948_Stat_Ok; +} + +ICM_20948_Status_e ICM_20948_execute_w(ICM_20948_Device_t *pdev, uint8_t regaddr, uint8_t *pdata, uint32_t len) +{ + if (pdev->_serif->write == NULL) + { + return ICM_20948_Stat_NotImpl; + } + return (*pdev->_serif->write)(regaddr, pdata, len, pdev->_serif->user); +} + +ICM_20948_Status_e ICM_20948_execute_r(ICM_20948_Device_t *pdev, uint8_t regaddr, uint8_t *pdata, uint32_t len) +{ + if (pdev->_serif->read == NULL) + { + return ICM_20948_Stat_NotImpl; + } + return (*pdev->_serif->read)(regaddr, pdata, len, pdev->_serif->user); +} + +//Transact directly with an I2C device, one byte at a time +//Used to configure a device before it is setup into a normal 0-3 peripheral slot +ICM_20948_Status_e ICM_20948_i2c_controller_periph4_txn(ICM_20948_Device_t *pdev, uint8_t addr, uint8_t reg, uint8_t *data, uint8_t len, bool Rw, bool send_reg_addr) +{ + // Thanks MikeFair! // https://github.com/kriswiner/MPU9250/issues/86 + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + addr = (((Rw) ? 0x80 : 0x00) | addr); + + retval = ICM_20948_set_bank(pdev, 3); + retval = ICM_20948_execute_w(pdev, AGB3_REG_I2C_PERIPH4_ADDR, (uint8_t *)&addr, 1); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + retval = ICM_20948_set_bank(pdev, 3); + retval = ICM_20948_execute_w(pdev, AGB3_REG_I2C_PERIPH4_REG, (uint8_t *)®, 1); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + ICM_20948_I2C_PERIPH4_CTRL_t ctrl; + ctrl.EN = 1; + ctrl.INT_EN = false; + ctrl.DLY = 0; + ctrl.REG_DIS = !send_reg_addr; + + ICM_20948_I2C_MST_STATUS_t i2c_mst_status; + bool txn_failed = false; + uint16_t nByte = 0; + + while (nByte < len) + { + if (!Rw) + { + retval = ICM_20948_set_bank(pdev, 3); + retval = ICM_20948_execute_w(pdev, AGB3_REG_I2C_PERIPH4_DO, (uint8_t *)&(data[nByte]), 1); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + } + + // Kick off txn + retval = ICM_20948_set_bank(pdev, 3); + retval = ICM_20948_execute_w(pdev, AGB3_REG_I2C_PERIPH4_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_I2C_PERIPH4_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + // long tsTimeout = millis() + 3000; // Emergency timeout for txn (hard coded to 3 secs) + uint32_t max_cycles = 1000; + uint32_t count = 0; + bool peripheral4Done = false; + while (!peripheral4Done) + { + retval = ICM_20948_set_bank(pdev, 0); + retval = ICM_20948_execute_r(pdev, AGB0_REG_I2C_MST_STATUS, (uint8_t *)&i2c_mst_status, 1); + + peripheral4Done = (i2c_mst_status.I2C_PERIPH4_DONE /*| (millis() > tsTimeout) */); //Avoid forever-loops + peripheral4Done |= (count >= max_cycles); + count++; + } + txn_failed = (i2c_mst_status.I2C_PERIPH4_NACK /*| (millis() > tsTimeout) */); + txn_failed |= (count >= max_cycles); + if (txn_failed) + break; + + if (Rw) + { + retval = ICM_20948_set_bank(pdev, 3); + retval = ICM_20948_execute_r(pdev, AGB3_REG_I2C_PERIPH4_DI, &data[nByte], 1); + } + + nByte++; + } + + if (txn_failed) + { + //We often fail here if mag is stuck + return ICM_20948_Stat_Err; + } + + return retval; +} + +ICM_20948_Status_e ICM_20948_i2c_master_single_w(ICM_20948_Device_t *pdev, uint8_t addr, uint8_t reg, uint8_t *data) +{ + return ICM_20948_i2c_controller_periph4_txn(pdev, addr, reg, data, 1, false, true); +} + +ICM_20948_Status_e ICM_20948_i2c_master_single_r(ICM_20948_Device_t *pdev, uint8_t addr, uint8_t reg, uint8_t *data) +{ + return ICM_20948_i2c_controller_periph4_txn(pdev, addr, reg, data, 1, true, true); +} + +ICM_20948_Status_e ICM_20948_set_bank(ICM_20948_Device_t *pdev, uint8_t bank) +{ + if (bank > 3) + { + return ICM_20948_Stat_ParamErr; + } // Only 4 possible banks + + if (bank == pdev->_last_bank) // Do we need to change bank? + return ICM_20948_Stat_Ok; // Bail if we don't need to change bank to avoid unnecessary bus traffic + + pdev->_last_bank = bank; // Store the requested bank (before we bit-shift) + bank = (bank << 4) & 0x30; // bits 5:4 of REG_BANK_SEL + return ICM_20948_execute_w(pdev, REG_BANK_SEL, &bank, 1); +} + +ICM_20948_Status_e ICM_20948_sw_reset(ICM_20948_Device_t *pdev) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + ICM_20948_PWR_MGMT_1_t reg; + + ICM_20948_set_bank(pdev, 0); // Must be in the right bank + + retval = ICM_20948_execute_r(pdev, AGB0_REG_PWR_MGMT_1, (uint8_t *)®, sizeof(ICM_20948_PWR_MGMT_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + reg.DEVICE_RESET = 1; + + retval = ICM_20948_execute_w(pdev, AGB0_REG_PWR_MGMT_1, (uint8_t *)®, sizeof(ICM_20948_PWR_MGMT_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_sleep(ICM_20948_Device_t *pdev, bool on) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + ICM_20948_PWR_MGMT_1_t reg; + + ICM_20948_set_bank(pdev, 0); // Must be in the right bank + + retval = ICM_20948_execute_r(pdev, AGB0_REG_PWR_MGMT_1, (uint8_t *)®, sizeof(ICM_20948_PWR_MGMT_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + if (on) + { + reg.SLEEP = 1; + } + else + { + reg.SLEEP = 0; + } + + retval = ICM_20948_execute_w(pdev, AGB0_REG_PWR_MGMT_1, (uint8_t *)®, sizeof(ICM_20948_PWR_MGMT_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_low_power(ICM_20948_Device_t *pdev, bool on) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + ICM_20948_PWR_MGMT_1_t reg; + + ICM_20948_set_bank(pdev, 0); // Must be in the right bank + + retval = ICM_20948_execute_r(pdev, AGB0_REG_PWR_MGMT_1, (uint8_t *)®, sizeof(ICM_20948_PWR_MGMT_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + if (on) + { + reg.LP_EN = 1; + } + else + { + reg.LP_EN = 0; + } + + retval = ICM_20948_execute_w(pdev, AGB0_REG_PWR_MGMT_1, (uint8_t *)®, sizeof(ICM_20948_PWR_MGMT_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_set_clock_source(ICM_20948_Device_t *pdev, ICM_20948_PWR_MGMT_1_CLKSEL_e source) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + ICM_20948_PWR_MGMT_1_t reg; + + ICM_20948_set_bank(pdev, 0); // Must be in the right bank + + retval = ICM_20948_execute_r(pdev, AGB0_REG_PWR_MGMT_1, (uint8_t *)®, sizeof(ICM_20948_PWR_MGMT_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + reg.CLKSEL = source; + + retval = ICM_20948_execute_w(pdev, AGB0_REG_PWR_MGMT_1, (uint8_t *)®, sizeof(ICM_20948_PWR_MGMT_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_get_who_am_i(ICM_20948_Device_t *pdev, uint8_t *whoami) +{ + if (whoami == NULL) + { + return ICM_20948_Stat_ParamErr; + } + ICM_20948_set_bank(pdev, 0); // Must be in the right bank + return ICM_20948_execute_r(pdev, AGB0_REG_WHO_AM_I, whoami, 1); +} + +ICM_20948_Status_e ICM_20948_check_id(ICM_20948_Device_t *pdev) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + uint8_t whoami = 0x00; + retval = ICM_20948_get_who_am_i(pdev, &whoami); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + if (whoami != ICM_20948_WHOAMI) + { + return ICM_20948_Stat_WrongID; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_data_ready(ICM_20948_Device_t *pdev) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + ICM_20948_INT_STATUS_1_t reg; + retval = ICM_20948_set_bank(pdev, 0); // Must be in the right bank + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_r(pdev, AGB0_REG_INT_STATUS_1, (uint8_t *)®, sizeof(ICM_20948_INT_STATUS_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + if (!reg.RAW_DATA_0_RDY_INT) + { + retval = ICM_20948_Stat_NoData; + } + return retval; +} + +// Interrupt Configuration +ICM_20948_Status_e ICM_20948_int_pin_cfg(ICM_20948_Device_t *pdev, ICM_20948_INT_PIN_CFG_t *write, ICM_20948_INT_PIN_CFG_t *read) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + retval = ICM_20948_set_bank(pdev, 0); // Must be in the right bank + if (write != NULL) + { // write first, if available + retval = ICM_20948_execute_w(pdev, AGB0_REG_INT_PIN_CONFIG, (uint8_t *)write, sizeof(ICM_20948_INT_PIN_CFG_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + } + if (read != NULL) + { // then read, to allow for verification + retval = ICM_20948_execute_r(pdev, AGB0_REG_INT_PIN_CONFIG, (uint8_t *)read, sizeof(ICM_20948_INT_PIN_CFG_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + } + return retval; +} + +ICM_20948_Status_e ICM_20948_int_enable(ICM_20948_Device_t *pdev, ICM_20948_INT_enable_t *write, ICM_20948_INT_enable_t *read) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + ICM_20948_INT_ENABLE_t en_0; + ICM_20948_INT_ENABLE_1_t en_1; + ICM_20948_INT_ENABLE_2_t en_2; + ICM_20948_INT_ENABLE_3_t en_3; + + retval = ICM_20948_set_bank(pdev, 0); // Must be in the right bank + + if (write != NULL) + { // If the write pointer is not NULL then write to the registers BEFORE reading + en_0.I2C_MST_INT_EN = write->I2C_MST_INT_EN; + en_0.DMP_INT1_EN = write->DMP_INT1_EN; + en_0.PLL_READY_EN = write->PLL_RDY_EN; + en_0.WOM_INT_EN = write->WOM_INT_EN; + en_0.reserved_0 = 0; // Clear RAM garbage + en_0.REG_WOF_EN = write->REG_WOF_EN; + en_1.RAW_DATA_0_RDY_EN = write->RAW_DATA_0_RDY_EN; + en_1.reserved_0 = 0; // Clear RAM garbage + en_2.individual.FIFO_OVERFLOW_EN_4 = write->FIFO_OVERFLOW_EN_4; + en_2.individual.FIFO_OVERFLOW_EN_3 = write->FIFO_OVERFLOW_EN_3; + en_2.individual.FIFO_OVERFLOW_EN_2 = write->FIFO_OVERFLOW_EN_2; + en_2.individual.FIFO_OVERFLOW_EN_1 = write->FIFO_OVERFLOW_EN_1; + en_2.individual.FIFO_OVERFLOW_EN_0 = write->FIFO_OVERFLOW_EN_0; + en_2.individual.reserved_0 = 0; // Clear RAM garbage + en_3.individual.FIFO_WM_EN_4 = write->FIFO_WM_EN_4; + en_3.individual.FIFO_WM_EN_3 = write->FIFO_WM_EN_3; + en_3.individual.FIFO_WM_EN_2 = write->FIFO_WM_EN_2; + en_3.individual.FIFO_WM_EN_1 = write->FIFO_WM_EN_1; + en_3.individual.FIFO_WM_EN_0 = write->FIFO_WM_EN_0; + en_3.individual.reserved_0 = 0; // Clear RAM garbage + + retval = ICM_20948_execute_w(pdev, AGB0_REG_INT_ENABLE, (uint8_t *)&en_0, sizeof(ICM_20948_INT_ENABLE_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_w(pdev, AGB0_REG_INT_ENABLE_1, (uint8_t *)&en_1, sizeof(ICM_20948_INT_ENABLE_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_w(pdev, AGB0_REG_INT_ENABLE_2, (uint8_t *)&en_2, sizeof(ICM_20948_INT_ENABLE_2_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_w(pdev, AGB0_REG_INT_ENABLE_3, (uint8_t *)&en_3, sizeof(ICM_20948_INT_ENABLE_3_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + } + + if (read != NULL) + { // If read pointer is not NULL then read the registers (if write is not NULL then this should read back the results of write into read) + retval = ICM_20948_execute_r(pdev, AGB0_REG_INT_ENABLE, (uint8_t *)&en_0, sizeof(ICM_20948_INT_ENABLE_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_r(pdev, AGB0_REG_INT_ENABLE_1, (uint8_t *)&en_1, sizeof(ICM_20948_INT_ENABLE_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_r(pdev, AGB0_REG_INT_ENABLE_2, (uint8_t *)&en_2, sizeof(ICM_20948_INT_ENABLE_2_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_r(pdev, AGB0_REG_INT_ENABLE_3, (uint8_t *)&en_3, sizeof(ICM_20948_INT_ENABLE_3_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + read->I2C_MST_INT_EN = en_0.I2C_MST_INT_EN; + read->DMP_INT1_EN = en_0.DMP_INT1_EN; + read->PLL_RDY_EN = en_0.PLL_READY_EN; + read->WOM_INT_EN = en_0.WOM_INT_EN; + read->REG_WOF_EN = en_0.REG_WOF_EN; + read->RAW_DATA_0_RDY_EN = en_1.RAW_DATA_0_RDY_EN; + read->FIFO_OVERFLOW_EN_4 = en_2.individual.FIFO_OVERFLOW_EN_4; + read->FIFO_OVERFLOW_EN_3 = en_2.individual.FIFO_OVERFLOW_EN_3; + read->FIFO_OVERFLOW_EN_2 = en_2.individual.FIFO_OVERFLOW_EN_2; + read->FIFO_OVERFLOW_EN_1 = en_2.individual.FIFO_OVERFLOW_EN_1; + read->FIFO_OVERFLOW_EN_0 = en_2.individual.FIFO_OVERFLOW_EN_0; + read->FIFO_WM_EN_4 = en_3.individual.FIFO_WM_EN_4; + read->FIFO_WM_EN_3 = en_3.individual.FIFO_WM_EN_3; + read->FIFO_WM_EN_2 = en_3.individual.FIFO_WM_EN_2; + read->FIFO_WM_EN_1 = en_3.individual.FIFO_WM_EN_1; + read->FIFO_WM_EN_0 = en_3.individual.FIFO_WM_EN_0; + } + + return retval; +} + +ICM_20948_Status_e ICM_20948_wom_threshold(ICM_20948_Device_t *pdev, ICM_20948_ACCEL_WOM_THR_t *write, ICM_20948_ACCEL_WOM_THR_t *read) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + ICM_20948_ACCEL_WOM_THR_t thr; + + retval = ICM_20948_set_bank(pdev, 2); // Must be in the right bank + + if (write != NULL) + { // If the write pointer is not NULL then write to the registers BEFORE reading + thr.WOM_THRESHOLD = write->WOM_THRESHOLD; + + retval = ICM_20948_execute_w(pdev, AGB2_REG_ACCEL_WOM_THR, (uint8_t *)&thr, sizeof(ICM_20948_ACCEL_WOM_THR_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + } + + if (read != NULL) + { // If read pointer is not NULL then read the registers (if write is not NULL then this should read back the results of write into read) + retval = ICM_20948_execute_r(pdev, AGB2_REG_ACCEL_WOM_THR, (uint8_t *)&thr, sizeof(ICM_20948_ACCEL_WOM_THR_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + read->WOM_THRESHOLD = thr.WOM_THRESHOLD; + } + + return retval; +} + +ICM_20948_Status_e ICM_20948_set_sample_mode(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, ICM_20948_LP_CONFIG_CYCLE_e mode) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + ICM_20948_LP_CONFIG_t reg; + + if (!(sensors & (ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr | ICM_20948_Internal_Mst))) + { + return ICM_20948_Stat_SensorNotSupported; + } + + retval = ICM_20948_set_bank(pdev, 0); // Must be in the right bank + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_r(pdev, AGB0_REG_LP_CONFIG, (uint8_t *)®, sizeof(ICM_20948_LP_CONFIG_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + if (sensors & ICM_20948_Internal_Acc) + { + reg.ACCEL_CYCLE = mode; + } // Set all desired sensors to this setting + if (sensors & ICM_20948_Internal_Gyr) + { + reg.GYRO_CYCLE = mode; + } + if (sensors & ICM_20948_Internal_Mst) + { + reg.I2C_MST_CYCLE = mode; + } + + retval = ICM_20948_execute_w(pdev, AGB0_REG_LP_CONFIG, (uint8_t *)®, sizeof(ICM_20948_LP_CONFIG_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + // Check the data was written correctly + retval = ICM_20948_execute_r(pdev, AGB0_REG_LP_CONFIG, (uint8_t *)®, sizeof(ICM_20948_LP_CONFIG_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + if (sensors & ICM_20948_Internal_Acc) + { + if (reg.ACCEL_CYCLE != mode) retval = ICM_20948_Stat_Err; + } + if (sensors & ICM_20948_Internal_Gyr) + { + if (reg.GYRO_CYCLE != mode) retval = ICM_20948_Stat_Err; + } + if (sensors & ICM_20948_Internal_Mst) + { + if (reg.I2C_MST_CYCLE != mode) retval = ICM_20948_Stat_Err; + } + + return retval; +} + +ICM_20948_Status_e ICM_20948_set_full_scale(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, ICM_20948_fss_t fss) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + if (!(sensors & (ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr))) + { + return ICM_20948_Stat_SensorNotSupported; + } + + if (sensors & ICM_20948_Internal_Acc) + { + ICM_20948_ACCEL_CONFIG_t reg; + retval |= ICM_20948_set_bank(pdev, 2); // Must be in the right bank + retval |= ICM_20948_execute_r(pdev, AGB2_REG_ACCEL_CONFIG, (uint8_t *)®, sizeof(ICM_20948_ACCEL_CONFIG_t)); + reg.ACCEL_FS_SEL = fss.a; + retval |= ICM_20948_execute_w(pdev, AGB2_REG_ACCEL_CONFIG, (uint8_t *)®, sizeof(ICM_20948_ACCEL_CONFIG_t)); + // Check the data was written correctly + retval |= ICM_20948_execute_r(pdev, AGB2_REG_ACCEL_CONFIG, (uint8_t *)®, sizeof(ICM_20948_ACCEL_CONFIG_t)); + if (reg.ACCEL_FS_SEL != fss.a) retval |= ICM_20948_Stat_Err; + } + if (sensors & ICM_20948_Internal_Gyr) + { + ICM_20948_GYRO_CONFIG_1_t reg; + retval |= ICM_20948_set_bank(pdev, 2); // Must be in the right bank + retval |= ICM_20948_execute_r(pdev, AGB2_REG_GYRO_CONFIG_1, (uint8_t *)®, sizeof(ICM_20948_GYRO_CONFIG_1_t)); + reg.GYRO_FS_SEL = fss.g; + retval |= ICM_20948_execute_w(pdev, AGB2_REG_GYRO_CONFIG_1, (uint8_t *)®, sizeof(ICM_20948_GYRO_CONFIG_1_t)); + // Check the data was written correctly + retval |= ICM_20948_execute_r(pdev, AGB2_REG_GYRO_CONFIG_1, (uint8_t *)®, sizeof(ICM_20948_GYRO_CONFIG_1_t)); + if (reg.GYRO_FS_SEL != fss.g) retval |= ICM_20948_Stat_Err; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_set_dlpf_cfg(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, ICM_20948_dlpcfg_t cfg) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + if (!(sensors & (ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr))) + { + return ICM_20948_Stat_SensorNotSupported; + } + + if (sensors & ICM_20948_Internal_Acc) + { + ICM_20948_ACCEL_CONFIG_t reg; + retval |= ICM_20948_set_bank(pdev, 2); // Must be in the right bank + retval |= ICM_20948_execute_r(pdev, AGB2_REG_ACCEL_CONFIG, (uint8_t *)®, sizeof(ICM_20948_ACCEL_CONFIG_t)); + reg.ACCEL_DLPFCFG = cfg.a; + retval |= ICM_20948_execute_w(pdev, AGB2_REG_ACCEL_CONFIG, (uint8_t *)®, sizeof(ICM_20948_ACCEL_CONFIG_t)); + // Check the data was written correctly + retval |= ICM_20948_execute_r(pdev, AGB2_REG_ACCEL_CONFIG, (uint8_t *)®, sizeof(ICM_20948_ACCEL_CONFIG_t)); + if (reg.ACCEL_DLPFCFG != cfg.a) retval |= ICM_20948_Stat_Err; + } + if (sensors & ICM_20948_Internal_Gyr) + { + ICM_20948_GYRO_CONFIG_1_t reg; + retval |= ICM_20948_set_bank(pdev, 2); // Must be in the right bank + retval |= ICM_20948_execute_r(pdev, AGB2_REG_GYRO_CONFIG_1, (uint8_t *)®, sizeof(ICM_20948_GYRO_CONFIG_1_t)); + reg.GYRO_DLPFCFG = cfg.g; + retval |= ICM_20948_execute_w(pdev, AGB2_REG_GYRO_CONFIG_1, (uint8_t *)®, sizeof(ICM_20948_GYRO_CONFIG_1_t)); + // Check the data was written correctly + retval |= ICM_20948_execute_r(pdev, AGB2_REG_GYRO_CONFIG_1, (uint8_t *)®, sizeof(ICM_20948_GYRO_CONFIG_1_t)); + if (reg.GYRO_DLPFCFG != cfg.g) retval |= ICM_20948_Stat_Err; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_enable_dlpf(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, bool enable) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + if (!(sensors & (ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr))) + { + return ICM_20948_Stat_SensorNotSupported; + } + + if (sensors & ICM_20948_Internal_Acc) + { + ICM_20948_ACCEL_CONFIG_t reg; + retval |= ICM_20948_set_bank(pdev, 2); // Must be in the right bank + retval |= ICM_20948_execute_r(pdev, AGB2_REG_ACCEL_CONFIG, (uint8_t *)®, sizeof(ICM_20948_ACCEL_CONFIG_t)); + if (enable) + { + reg.ACCEL_FCHOICE = 1; + } + else + { + reg.ACCEL_FCHOICE = 0; + } + retval |= ICM_20948_execute_w(pdev, AGB2_REG_ACCEL_CONFIG, (uint8_t *)®, sizeof(ICM_20948_ACCEL_CONFIG_t)); + // Check the data was written correctly + retval |= ICM_20948_execute_r(pdev, AGB2_REG_ACCEL_CONFIG, (uint8_t *)®, sizeof(ICM_20948_ACCEL_CONFIG_t)); + if (enable) + { + if (reg.ACCEL_FCHOICE != 1) retval |= ICM_20948_Stat_Err; + } + else + { + if (reg.ACCEL_FCHOICE != 0) retval |= ICM_20948_Stat_Err; + } + } + if (sensors & ICM_20948_Internal_Gyr) + { + ICM_20948_GYRO_CONFIG_1_t reg; + retval |= ICM_20948_set_bank(pdev, 2); // Must be in the right bank + retval |= ICM_20948_execute_r(pdev, AGB2_REG_GYRO_CONFIG_1, (uint8_t *)®, sizeof(ICM_20948_GYRO_CONFIG_1_t)); + if (enable) + { + reg.GYRO_FCHOICE = 1; + } + else + { + reg.GYRO_FCHOICE = 0; + } + retval |= ICM_20948_execute_w(pdev, AGB2_REG_GYRO_CONFIG_1, (uint8_t *)®, sizeof(ICM_20948_GYRO_CONFIG_1_t)); + // Check the data was written correctly + retval |= ICM_20948_execute_r(pdev, AGB2_REG_GYRO_CONFIG_1, (uint8_t *)®, sizeof(ICM_20948_GYRO_CONFIG_1_t)); + if (enable) + { + if (reg.GYRO_FCHOICE != 1) retval |= ICM_20948_Stat_Err; + } + else + { + if (reg.GYRO_FCHOICE != 0) retval |= ICM_20948_Stat_Err; + } + } + return retval; +} + +ICM_20948_Status_e ICM_20948_set_sample_rate(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, ICM_20948_smplrt_t smplrt) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + if (!(sensors & (ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr))) + { + return ICM_20948_Stat_SensorNotSupported; + } + + if (sensors & ICM_20948_Internal_Acc) + { + retval |= ICM_20948_set_bank(pdev, 2); // Must be in the right bank + uint8_t div1 = (smplrt.a >> 8); // Thank you @yanivamichy #109 + uint8_t div2 = (smplrt.a & 0xFF); + retval |= ICM_20948_execute_w(pdev, AGB2_REG_ACCEL_SMPLRT_DIV_1, &div1, 1); + retval |= ICM_20948_execute_w(pdev, AGB2_REG_ACCEL_SMPLRT_DIV_2, &div2, 1); + } + if (sensors & ICM_20948_Internal_Gyr) + { + retval |= ICM_20948_set_bank(pdev, 2); // Must be in the right bank + uint8_t div = (smplrt.g); + retval |= ICM_20948_execute_w(pdev, AGB2_REG_GYRO_SMPLRT_DIV, &div, 1); + } + return retval; +} + +// Interface Things +ICM_20948_Status_e ICM_20948_i2c_master_passthrough(ICM_20948_Device_t *pdev, bool passthrough) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + ICM_20948_INT_PIN_CFG_t reg; + retval = ICM_20948_set_bank(pdev, 0); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_r(pdev, AGB0_REG_INT_PIN_CONFIG, (uint8_t *)®, sizeof(ICM_20948_INT_PIN_CFG_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + reg.BYPASS_EN = passthrough; + retval = ICM_20948_execute_w(pdev, AGB0_REG_INT_PIN_CONFIG, (uint8_t *)®, sizeof(ICM_20948_INT_PIN_CFG_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + return retval; +} + +ICM_20948_Status_e ICM_20948_i2c_master_enable(ICM_20948_Device_t *pdev, bool enable) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + // Disable BYPASS_EN + retval = ICM_20948_i2c_master_passthrough(pdev, false); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + ICM_20948_I2C_MST_CTRL_t ctrl; + retval = ICM_20948_set_bank(pdev, 3); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_r(pdev, AGB3_REG_I2C_MST_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_I2C_MST_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + ctrl.I2C_MST_CLK = 0x07; // corresponds to 345.6 kHz, good for up to 400 kHz + ctrl.I2C_MST_P_NSR = 1; + retval = ICM_20948_execute_w(pdev, AGB3_REG_I2C_MST_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_I2C_MST_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + ICM_20948_USER_CTRL_t reg; + retval = ICM_20948_set_bank(pdev, 0); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_r(pdev, AGB0_REG_USER_CTRL, (uint8_t *)®, sizeof(ICM_20948_USER_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + if (enable) + { + reg.I2C_MST_EN = 1; + } + else + { + reg.I2C_MST_EN = 0; + } + retval = ICM_20948_execute_w(pdev, AGB0_REG_USER_CTRL, (uint8_t *)®, sizeof(ICM_20948_USER_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + return retval; +} + +ICM_20948_Status_e ICM_20948_i2c_master_reset(ICM_20948_Device_t *pdev) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + ICM_20948_USER_CTRL_t ctrl; + retval = ICM_20948_set_bank(pdev, 0); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + retval = ICM_20948_execute_r(pdev, AGB0_REG_USER_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_USER_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + ctrl.I2C_MST_RST = 1; //Reset! + + retval = ICM_20948_execute_w(pdev, AGB0_REG_USER_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_USER_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_i2c_controller_configure_peripheral(ICM_20948_Device_t *pdev, uint8_t peripheral, uint8_t addr, uint8_t reg, uint8_t len, bool Rw, bool enable, bool data_only, bool grp, bool swap, uint8_t dataOut) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + uint8_t periph_addr_reg; + uint8_t periph_reg_reg; + uint8_t periph_ctrl_reg; + uint8_t periph_do_reg; + + switch (peripheral) + { + case 0: + periph_addr_reg = AGB3_REG_I2C_PERIPH0_ADDR; + periph_reg_reg = AGB3_REG_I2C_PERIPH0_REG; + periph_ctrl_reg = AGB3_REG_I2C_PERIPH0_CTRL; + periph_do_reg = AGB3_REG_I2C_PERIPH0_DO; + break; + case 1: + periph_addr_reg = AGB3_REG_I2C_PERIPH1_ADDR; + periph_reg_reg = AGB3_REG_I2C_PERIPH1_REG; + periph_ctrl_reg = AGB3_REG_I2C_PERIPH1_CTRL; + periph_do_reg = AGB3_REG_I2C_PERIPH1_DO; + break; + case 2: + periph_addr_reg = AGB3_REG_I2C_PERIPH2_ADDR; + periph_reg_reg = AGB3_REG_I2C_PERIPH2_REG; + periph_ctrl_reg = AGB3_REG_I2C_PERIPH2_CTRL; + periph_do_reg = AGB3_REG_I2C_PERIPH2_DO; + break; + case 3: + periph_addr_reg = AGB3_REG_I2C_PERIPH3_ADDR; + periph_reg_reg = AGB3_REG_I2C_PERIPH3_REG; + periph_ctrl_reg = AGB3_REG_I2C_PERIPH3_CTRL; + periph_do_reg = AGB3_REG_I2C_PERIPH3_DO; + break; + default: + return ICM_20948_Stat_ParamErr; + } + + retval = ICM_20948_set_bank(pdev, 3); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + // Set the peripheral address and the Rw flag + ICM_20948_I2C_PERIPHX_ADDR_t address; + address.ID = addr; + if (Rw) + { + address.RNW = 1; + } + else + { + address.RNW = 0; // Make sure bit is clear (just in case there is any garbage in that RAM location) + } + retval = ICM_20948_execute_w(pdev, periph_addr_reg, (uint8_t *)&address, sizeof(ICM_20948_I2C_PERIPHX_ADDR_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + // If we are setting up a write, configure the Data Out register too + if (!Rw) + { + ICM_20948_I2C_PERIPHX_DO_t dataOutByte; + dataOutByte.DO = dataOut; + retval = ICM_20948_execute_w(pdev, periph_do_reg, (uint8_t *)&dataOutByte, sizeof(ICM_20948_I2C_PERIPHX_DO_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + } + + // Set the peripheral sub-address (register address) + ICM_20948_I2C_PERIPHX_REG_t subaddress; + subaddress.REG = reg; + retval = ICM_20948_execute_w(pdev, periph_reg_reg, (uint8_t *)&subaddress, sizeof(ICM_20948_I2C_PERIPHX_REG_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + // Set up the control info + ICM_20948_I2C_PERIPHX_CTRL_t ctrl; + ctrl.LENG = len; + ctrl.EN = enable; + ctrl.REG_DIS = data_only; + ctrl.GRP = grp; + ctrl.BYTE_SW = swap; + retval = ICM_20948_execute_w(pdev, periph_ctrl_reg, (uint8_t *)&ctrl, sizeof(ICM_20948_I2C_PERIPHX_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + return retval; +} + +// Higher Level +ICM_20948_Status_e ICM_20948_get_agmt(ICM_20948_Device_t *pdev, ICM_20948_AGMT_t *pagmt) +{ + if (pagmt == NULL) + { + return ICM_20948_Stat_ParamErr; + } + + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + const uint8_t numbytes = 14 + 9; //Read Accel, gyro, temp, and 9 bytes of mag + uint8_t buff[numbytes]; + + // Get readings + retval |= ICM_20948_set_bank(pdev, 0); + retval |= ICM_20948_execute_r(pdev, (uint8_t)AGB0_REG_ACCEL_XOUT_H, buff, numbytes); + + pagmt->acc.axes.x = ((buff[0] << 8) | (buff[1] & 0xFF)); + pagmt->acc.axes.y = ((buff[2] << 8) | (buff[3] & 0xFF)); + pagmt->acc.axes.z = ((buff[4] << 8) | (buff[5] & 0xFF)); + + pagmt->gyr.axes.x = ((buff[6] << 8) | (buff[7] & 0xFF)); + pagmt->gyr.axes.y = ((buff[8] << 8) | (buff[9] & 0xFF)); + pagmt->gyr.axes.z = ((buff[10] << 8) | (buff[11] & 0xFF)); + + pagmt->tmp.val = ((buff[12] << 8) | (buff[13] & 0xFF)); + + pagmt->magStat1 = buff[14]; + pagmt->mag.axes.x = ((buff[16] << 8) | (buff[15] & 0xFF)); //Mag data is read little endian + pagmt->mag.axes.y = ((buff[18] << 8) | (buff[17] & 0xFF)); + pagmt->mag.axes.z = ((buff[20] << 8) | (buff[19] & 0xFF)); + pagmt->magStat2 = buff[22]; + + // Get settings to be able to compute scaled values + retval |= ICM_20948_set_bank(pdev, 2); + ICM_20948_ACCEL_CONFIG_t acfg; + retval |= ICM_20948_execute_r(pdev, (uint8_t)AGB2_REG_ACCEL_CONFIG, (uint8_t *)&acfg, 1 * sizeof(acfg)); + pagmt->fss.a = acfg.ACCEL_FS_SEL; // Worth noting that without explicitly setting the FS range of the accelerometer it was showing the register value for +/- 2g but the reported values were actually scaled to the +/- 16g range + // Wait a minute... now it seems like this problem actually comes from the digital low-pass filter. When enabled the value is 1/8 what it should be... + retval |= ICM_20948_set_bank(pdev, 2); + ICM_20948_GYRO_CONFIG_1_t gcfg1; + retval |= ICM_20948_execute_r(pdev, (uint8_t)AGB2_REG_GYRO_CONFIG_1, (uint8_t *)&gcfg1, 1 * sizeof(gcfg1)); + pagmt->fss.g = gcfg1.GYRO_FS_SEL; + ICM_20948_ACCEL_CONFIG_2_t acfg2; + retval |= ICM_20948_execute_r(pdev, (uint8_t)AGB2_REG_ACCEL_CONFIG_2, (uint8_t *)&acfg2, 1 * sizeof(acfg2)); + + return retval; +} + +// FIFO + +ICM_20948_Status_e ICM_20948_enable_FIFO(ICM_20948_Device_t *pdev, bool enable) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + ICM_20948_USER_CTRL_t ctrl; + retval = ICM_20948_set_bank(pdev, 0); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + retval = ICM_20948_execute_r(pdev, AGB0_REG_USER_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_USER_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + if (enable) + ctrl.FIFO_EN = 1; + else + ctrl.FIFO_EN = 0; + + retval = ICM_20948_execute_w(pdev, AGB0_REG_USER_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_USER_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_reset_FIFO(ICM_20948_Device_t *pdev) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + ICM_20948_FIFO_RST_t ctrl; + retval = ICM_20948_set_bank(pdev, 0); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + retval = ICM_20948_execute_r(pdev, AGB0_REG_FIFO_RST, (uint8_t *)&ctrl, sizeof(ICM_20948_FIFO_RST_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + ctrl.FIFO_RESET = 0x1F; // Datasheet says "FIFO_RESET[4:0]" + + retval = ICM_20948_execute_w(pdev, AGB0_REG_FIFO_RST, (uint8_t *)&ctrl, sizeof(ICM_20948_FIFO_RST_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + //delay ??? + + ctrl.FIFO_RESET = 0x1E; // The InvenSense Nucleo examples write 0x1F followed by 0x1E + + retval = ICM_20948_execute_w(pdev, AGB0_REG_FIFO_RST, (uint8_t *)&ctrl, sizeof(ICM_20948_FIFO_RST_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + return retval; +} + +ICM_20948_Status_e ICM_20948_set_FIFO_mode(ICM_20948_Device_t *pdev, bool snapshot) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + ICM_20948_FIFO_MODE_t ctrl; + retval = ICM_20948_set_bank(pdev, 0); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + retval = ICM_20948_execute_r(pdev, AGB0_REG_FIFO_MODE, (uint8_t *)&ctrl, sizeof(ICM_20948_FIFO_MODE_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + if (snapshot) + ctrl.FIFO_MODE = 0x1F; // Datasheet says "FIFO_MODE[4:0]" + else + ctrl.FIFO_MODE = 0; + + retval = ICM_20948_execute_w(pdev, AGB0_REG_FIFO_MODE, (uint8_t *)&ctrl, sizeof(ICM_20948_FIFO_MODE_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_get_FIFO_count(ICM_20948_Device_t *pdev, uint16_t *count) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + ICM_20948_FIFO_COUNTH_t ctrlh; + ICM_20948_FIFO_COUNTL_t ctrll; + retval = ICM_20948_set_bank(pdev, 0); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + retval = ICM_20948_execute_r(pdev, AGB0_REG_FIFO_COUNT_H, (uint8_t *)&ctrlh, sizeof(ICM_20948_FIFO_COUNTH_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + ctrlh.FIFO_COUNTH &= 0x1F; // Datasheet says "FIFO_CNT[12:8]" + + retval = ICM_20948_execute_r(pdev, AGB0_REG_FIFO_COUNT_L, (uint8_t *)&ctrll, sizeof(ICM_20948_FIFO_COUNTL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + *count = (((uint16_t)ctrlh.FIFO_COUNTH) << 8) | (uint16_t)ctrll.FIFO_COUNTL; + + return retval; +} + +ICM_20948_Status_e ICM_20948_read_FIFO(ICM_20948_Device_t *pdev, uint8_t *data, uint8_t len) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + retval = ICM_20948_set_bank(pdev, 0); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + retval = ICM_20948_execute_r(pdev, AGB0_REG_FIFO_R_W, data, len); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + return retval; +} + +// DMP + +ICM_20948_Status_e ICM_20948_enable_DMP(ICM_20948_Device_t *pdev, bool enable) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + ICM_20948_USER_CTRL_t ctrl; + retval = ICM_20948_set_bank(pdev, 0); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + retval = ICM_20948_execute_r(pdev, AGB0_REG_USER_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_USER_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + if (enable) + ctrl.DMP_EN = 1; + else + ctrl.DMP_EN = 0; + + retval = ICM_20948_execute_w(pdev, AGB0_REG_USER_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_USER_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_reset_DMP(ICM_20948_Device_t *pdev) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + ICM_20948_USER_CTRL_t ctrl; + retval = ICM_20948_set_bank(pdev, 0); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + retval = ICM_20948_execute_r(pdev, AGB0_REG_USER_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_USER_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + ctrl.DMP_RST = 1; + + retval = ICM_20948_execute_w(pdev, AGB0_REG_USER_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_USER_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_firmware_load(ICM_20948_Device_t *pdev) +{ +#if defined(ICM_20948_USE_DMP) + return (inv_icm20948_firmware_load(pdev, dmp3_image, sizeof(dmp3_image), DMP_LOAD_START)); +#else + return ICM_20948_Stat_DMPNotSupported; +#endif +} + +/** @brief Loads the DMP firmware from SRAM +* @param[in] data pointer where the image +* @param[in] size size if the image +* @param[in] load_addr address to loading the image +* @return 0 in case of success, -1 for any error +*/ +ICM_20948_Status_e inv_icm20948_firmware_load(ICM_20948_Device_t *pdev, const unsigned char *data_start, unsigned short size_start, unsigned short load_addr) +{ + int write_size; + ICM_20948_Status_e result = ICM_20948_Stat_Ok; + unsigned short memaddr; + const unsigned char *data; + unsigned short size; + unsigned char data_cmp[INV_MAX_SERIAL_READ]; + int flag = 0; + + if (pdev->_dmp_firmware_available == false) + return ICM_20948_Stat_DMPNotSupported; + + if (pdev->_firmware_loaded) + return ICM_20948_Stat_Ok; // Bail with no error if firmware is already loaded + + result = ICM_20948_sleep(pdev, false); // Make sure chip is awake + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + result = ICM_20948_low_power(pdev, false); // Make sure chip is not in low power state + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + // Write DMP memory + + data = data_start; + size = size_start; + memaddr = load_addr; + #ifdef ICM_20948_USE_PROGMEM_FOR_DMP + unsigned char data_not_pg[INV_MAX_SERIAL_READ]; // Suggested by @HyperKokichi in Issue #63 + #endif + while (size > 0) + { + //write_size = min(size, INV_MAX_SERIAL_WRITE); // Write in chunks of INV_MAX_SERIAL_WRITE + if (size <= INV_MAX_SERIAL_WRITE) // Write in chunks of INV_MAX_SERIAL_WRITE + write_size = size; + else + write_size = INV_MAX_SERIAL_WRITE; + if ((memaddr & 0xff) + write_size > 0x100) + { + // Moved across a bank + write_size = (memaddr & 0xff) + write_size - 0x100; + } +#ifdef ICM_20948_USE_PROGMEM_FOR_DMP + memcpy_P(data_not_pg, data, write_size); // Suggested by @HyperKokichi in Issue #63 + result = inv_icm20948_write_mems(pdev, memaddr, write_size, (unsigned char *)data_not_pg); +#else + result = inv_icm20948_write_mems(pdev, memaddr, write_size, (unsigned char *)data); +#endif + if (result != ICM_20948_Stat_Ok) + return result; + data += write_size; + size -= write_size; + memaddr += write_size; + } + + // Verify DMP memory + + data = data_start; + size = size_start; + memaddr = load_addr; + while (size > 0) + { + //write_size = min(size, INV_MAX_SERIAL_READ); // Read in chunks of INV_MAX_SERIAL_READ + if (size <= INV_MAX_SERIAL_READ) // Read in chunks of INV_MAX_SERIAL_READ + write_size = size; + else + write_size = INV_MAX_SERIAL_READ; + if ((memaddr & 0xff) + write_size > 0x100) + { + // Moved across a bank + write_size = (memaddr & 0xff) + write_size - 0x100; + } + result = inv_icm20948_read_mems(pdev, memaddr, write_size, data_cmp); + if (result != ICM_20948_Stat_Ok) + flag++; // Error, DMP not written correctly +#ifdef ICM_20948_USE_PROGMEM_FOR_DMP + memcpy_P(data_not_pg, data, write_size); // Suggested by @HyperKokichi in Issue #63 + if (memcmp(data_cmp, data_not_pg, write_size)) +#else + if (memcmp(data_cmp, data, write_size)) // Compare the data +#endif + return ICM_20948_Stat_DMPVerifyFail; + data += write_size; + size -= write_size; + memaddr += write_size; + } + + //Enable LP_EN since we disabled it at begining of this function. + result = ICM_20948_low_power(pdev, true); // Put chip into low power state + if (result != ICM_20948_Stat_Ok) + return result; + + if (!flag) + { + //Serial.println("DMP Firmware was updated successfully.."); + pdev->_firmware_loaded = true; + } + + return result; +} + +ICM_20948_Status_e ICM_20948_set_dmp_start_address(ICM_20948_Device_t *pdev, unsigned short address) +{ + ICM_20948_Status_e result = ICM_20948_Stat_Ok; + + if (pdev->_dmp_firmware_available == false) + return ICM_20948_Stat_DMPNotSupported; + + unsigned char start_address[2]; + + start_address[0] = (unsigned char)(address >> 8); + start_address[1] = (unsigned char)(address & 0xff); + + // result = ICM_20948_sleep(pdev, false); // Make sure chip is awake + // if (result != ICM_20948_Stat_Ok) + // { + // return result; + // } + // + // result = ICM_20948_low_power(pdev, false); // Make sure chip is not in low power state + // if (result != ICM_20948_Stat_Ok) + // { + // return result; + // } + + result = ICM_20948_set_bank(pdev, 2); // Set bank 2 + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + // Write the sensor control bits into memory address AGB2_REG_PRGM_START_ADDRH + result = ICM_20948_execute_w(pdev, AGB2_REG_PRGM_START_ADDRH, (uint8_t *)start_address, 2); + + return result; +} + +/** +* @brief Write data to a register in DMP memory +* @param[in] DMP memory address +* @param[in] number of byte to be written +* @param[out] output data from the register +* @return 0 if successful. +*/ +ICM_20948_Status_e inv_icm20948_write_mems(ICM_20948_Device_t *pdev, unsigned short reg, unsigned int length, const unsigned char *data) +{ + ICM_20948_Status_e result = ICM_20948_Stat_Ok; + unsigned int bytesWritten = 0; + unsigned int thisLen; + unsigned char lBankSelected; + unsigned char lStartAddrSelected; + + if (!data) + { + return ICM_20948_Stat_NoData; + } + + result = ICM_20948_set_bank(pdev, 0); // Set bank 0 + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + lBankSelected = (reg >> 8); + + if (lBankSelected != pdev->_last_mems_bank) + { + pdev->_last_mems_bank = lBankSelected; + result = ICM_20948_execute_w(pdev, AGB0_REG_MEM_BANK_SEL, &lBankSelected, 1); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + } + + while (bytesWritten < length) + { + lStartAddrSelected = (reg & 0xff); + + /* Sets the starting read or write address for the selected memory, inside of the selected page (see MEM_SEL Register). + Contents are changed after read or write of the selected memory. + This register must be written prior to each access to initialize the register to the proper starting address. + The address will auto increment during burst transactions. Two consecutive bursts without re-initializing the start address would skip one address. */ + + result = ICM_20948_execute_w(pdev, AGB0_REG_MEM_START_ADDR, &lStartAddrSelected, 1); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + if (length - bytesWritten <= INV_MAX_SERIAL_WRITE) + thisLen = length - bytesWritten; + else + thisLen = INV_MAX_SERIAL_WRITE; + + /* Write data */ + + result = ICM_20948_execute_w(pdev, AGB0_REG_MEM_R_W, (uint8_t *)&data[bytesWritten], thisLen); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + bytesWritten += thisLen; + reg += thisLen; + } + + return result; +} + +/** +* @brief Read data from a register in DMP memory +* @param[in] DMP memory address +* @param[in] number of byte to be read +* @param[in] input data from the register +* @return 0 if successful. +*/ +ICM_20948_Status_e inv_icm20948_read_mems(ICM_20948_Device_t *pdev, unsigned short reg, unsigned int length, unsigned char *data) +{ + ICM_20948_Status_e result = ICM_20948_Stat_Ok; + unsigned int bytesRead = 0; + unsigned int thisLen; + unsigned char lBankSelected; + unsigned char lStartAddrSelected; + + if (!data) + { + return ICM_20948_Stat_NoData; + } + + result = ICM_20948_set_bank(pdev, 0); // Set bank 0 + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + lBankSelected = (reg >> 8); + + if (lBankSelected != pdev->_last_mems_bank) + { + pdev->_last_mems_bank = lBankSelected; + result = ICM_20948_execute_w(pdev, AGB0_REG_MEM_BANK_SEL, &lBankSelected, 1); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + } + + while (bytesRead < length) + { + lStartAddrSelected = (reg & 0xff); + + /* Sets the starting read or write address for the selected memory, inside of the selected page (see MEM_SEL Register). + Contents are changed after read or write of the selected memory. + This register must be written prior to each access to initialize the register to the proper starting address. + The address will auto increment during burst transactions. Two consecutive bursts without re-initializing the start address would skip one address. */ + + result = ICM_20948_execute_w(pdev, AGB0_REG_MEM_START_ADDR, &lStartAddrSelected, 1); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + if (length - bytesRead <= INV_MAX_SERIAL_READ) + thisLen = length - bytesRead; + else + thisLen = INV_MAX_SERIAL_READ; + + /* Read data */ + + result = ICM_20948_execute_r(pdev, AGB0_REG_MEM_R_W, &data[bytesRead], thisLen); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + bytesRead += thisLen; + reg += thisLen; + } + + return result; +} + +ICM_20948_Status_e inv_icm20948_set_dmp_sensor_period(ICM_20948_Device_t *pdev, enum DMP_ODR_Registers odr_reg, uint16_t interval) +{ + // Set the ODR registers and clear the ODR counter + + // In order to set an ODR for a given sensor data, write 2-byte value to DMP using key defined above for a particular sensor. + // Setting value can be calculated as follows: + // Value = (DMP running rate (225Hz) / ODR ) - 1 + // E.g. For a 25Hz ODR rate, value= (225/25) -1 = 8. + + // During run-time, if an ODR is changed, the corresponding rate counter must be reset. + // To reset, write 2-byte {0,0} to DMP using keys below for a particular sensor: + + ICM_20948_Status_e result = ICM_20948_Stat_Ok; + ICM_20948_Status_e result2 = ICM_20948_Stat_Ok; + + if (pdev->_dmp_firmware_available == false) + return ICM_20948_Stat_DMPNotSupported; + + unsigned char odr_reg_val[2]; + odr_reg_val[0] = (unsigned char)(interval >> 8); + odr_reg_val[1] = (unsigned char)(interval & 0xff); + + unsigned char odr_count_zero[2] = {0x00, 0x00}; + + result = ICM_20948_sleep(pdev, false); // Make sure chip is awake + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + result = ICM_20948_low_power(pdev, false); // Make sure chip is not in low power state + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + switch (odr_reg) + { + case DMP_ODR_Reg_Cpass_Calibr: + { + result = inv_icm20948_write_mems(pdev, ODR_CPASS_CALIBR, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_CPASS_CALIBR, 2, (const unsigned char *)&odr_count_zero); + } + break; + case DMP_ODR_Reg_Gyro_Calibr: + { + result = inv_icm20948_write_mems(pdev, ODR_GYRO_CALIBR, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_GYRO_CALIBR, 2, (const unsigned char *)&odr_count_zero); + } + break; + case DMP_ODR_Reg_Pressure: + { + result = inv_icm20948_write_mems(pdev, ODR_PRESSURE, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_PRESSURE, 2, (const unsigned char *)&odr_count_zero); + } + break; + case DMP_ODR_Reg_Geomag: + { + result = inv_icm20948_write_mems(pdev, ODR_GEOMAG, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_GEOMAG, 2, (const unsigned char *)&odr_count_zero); + } + break; + case DMP_ODR_Reg_PQuat6: + { + result = inv_icm20948_write_mems(pdev, ODR_PQUAT6, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_PQUAT6, 2, (const unsigned char *)&odr_count_zero); + } + break; + case DMP_ODR_Reg_Quat9: + { + result = inv_icm20948_write_mems(pdev, ODR_QUAT9, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_QUAT9, 2, (const unsigned char *)&odr_count_zero); + } + break; + case DMP_ODR_Reg_Quat6: + { + result = inv_icm20948_write_mems(pdev, ODR_QUAT6, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_QUAT6, 2, (const unsigned char *)&odr_count_zero); + } + break; + case DMP_ODR_Reg_ALS: + { + result = inv_icm20948_write_mems(pdev, ODR_ALS, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_ALS, 2, (const unsigned char *)&odr_count_zero); + } + break; + case DMP_ODR_Reg_Cpass: + { + result = inv_icm20948_write_mems(pdev, ODR_CPASS, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_CPASS, 2, (const unsigned char *)&odr_count_zero); + } + break; + case DMP_ODR_Reg_Gyro: + { + result = inv_icm20948_write_mems(pdev, ODR_GYRO, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_GYRO, 2, (const unsigned char *)&odr_count_zero); + } + break; + case DMP_ODR_Reg_Accel: + { + result = inv_icm20948_write_mems(pdev, ODR_ACCEL, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_ACCEL, 2, (const unsigned char *)&odr_count_zero); + } + break; + default: + result = ICM_20948_Stat_InvalDMPRegister; + break; + } + + result = ICM_20948_low_power(pdev, true); // Put chip into low power state + if (result != ICM_20948_Stat_Ok) + return result; + + if (result2 > result) + result = result2; // Return the highest error + + return result; +} + +ICM_20948_Status_e inv_icm20948_enable_dmp_sensor(ICM_20948_Device_t *pdev, enum inv_icm20948_sensor sensor, int state) +{ + ICM_20948_Status_e result = ICM_20948_Stat_Ok; + + uint16_t inv_event_control = 0; // Use this to store the value for MOTION_EVENT_CTL + uint16_t data_rdy_status = 0; // Use this to store the value for DATA_RDY_STATUS + + if (pdev->_dmp_firmware_available == false) + return ICM_20948_Stat_DMPNotSupported; // Bail if DMP is not supported + + uint8_t androidSensor = sensor_type_2_android_sensor(sensor); // Convert sensor from enum inv_icm20948_sensor to Android numbering + + if (androidSensor >= ANDROID_SENSOR_NUM_MAX) + return ICM_20948_Stat_SensorNotSupported; // Bail if the sensor is not supported (TO DO: Support B2S etc) + + // Convert the Android sensor into a bit mask for DATA_OUT_CTL1 + uint16_t delta = inv_androidSensor_to_control_bits[androidSensor]; + if (delta == 0xFFFF) + return ICM_20948_Stat_SensorNotSupported; // Bail if the sensor is not supported + + // Convert the Android sensor number into a bitmask and set or clear that bit in _enabled_Android_0 / _enabled_Android_1 + unsigned long androidSensorAsBitMask; + if (androidSensor < 32) // Sensors 0-31 + { + androidSensorAsBitMask = 1L << androidSensor; + if (state == 0) // Should we disable the sensor? + { + pdev->_enabled_Android_0 &= ~androidSensorAsBitMask; // Clear the bit to disable the sensor + } + else + { + pdev->_enabled_Android_0 |= androidSensorAsBitMask; // Set the bit to enable the sensor + } + } + else // Sensors 32- + { + androidSensorAsBitMask = 1L << (androidSensor - 32); + if (state == 0) // Should we disable the sensor? + { + pdev->_enabled_Android_1 &= ~androidSensorAsBitMask; // Clear the bit to disable the sensor + } + else + { + pdev->_enabled_Android_1 |= androidSensorAsBitMask; // Set the bit to enable the sensor + } + } + + // Now we know androidSensor is valid, reconstruct the value for DATA_OUT_CTL1 from _enabled_Android_0 and _enabled_Android_0 + delta = 0; // Clear delta + for (int i = 0; i < 32; i++) + { + androidSensorAsBitMask = 1L << i; + if ((pdev->_enabled_Android_0 & androidSensorAsBitMask) > 0) // Check if the Android sensor (0-31) is enabled + { + delta |= inv_androidSensor_to_control_bits[i]; // If it is, or the required bits into delta + } + if ((pdev->_enabled_Android_1 & androidSensorAsBitMask) > 0) // Check if the Android sensor (32-) is enabled + { + delta |= inv_androidSensor_to_control_bits[i + 32]; // If it is, or the required bits into delta + } + // Also check which bits need to be set in the Data Ready Status and Motion Event Control registers + // Compare to INV_NEEDS_ACCEL_MASK, INV_NEEDS_GYRO_MASK and INV_NEEDS_COMPASS_MASK + if (((androidSensorAsBitMask & INV_NEEDS_ACCEL_MASK) > 0) || ((androidSensorAsBitMask & INV_NEEDS_ACCEL_MASK1) > 0)) + { + data_rdy_status |= DMP_Data_ready_Accel; + inv_event_control |= DMP_Motion_Event_Control_Accel_Calibr; + } + if (((androidSensorAsBitMask & INV_NEEDS_GYRO_MASK) > 0) || ((androidSensorAsBitMask & INV_NEEDS_GYRO_MASK1) > 0)) + { + data_rdy_status |= DMP_Data_ready_Gyro; + inv_event_control |= DMP_Motion_Event_Control_Gyro_Calibr; + } + if (((androidSensorAsBitMask & INV_NEEDS_COMPASS_MASK) > 0) || ((androidSensorAsBitMask & INV_NEEDS_COMPASS_MASK1) > 0)) + { + data_rdy_status |= DMP_Data_ready_Secondary_Compass; + inv_event_control |= DMP_Motion_Event_Control_Compass_Calibr; + } + } + + result = ICM_20948_sleep(pdev, false); // Make sure chip is awake + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + result = ICM_20948_low_power(pdev, false); // Make sure chip is not in low power state + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + // Check if Accel, Gyro/Gyro_Calibr or Compass_Calibr/Quat9/GeoMag/Compass are to be enabled. If they are then we need to request the accuracy data via header2. + uint16_t delta2 = 0; + if ((delta & DMP_Data_Output_Control_1_Accel) > 0) + { + delta2 |= DMP_Data_Output_Control_2_Accel_Accuracy; + } + if (((delta & DMP_Data_Output_Control_1_Gyro_Calibr) > 0) || ((delta & DMP_Data_Output_Control_1_Gyro) > 0)) + { + delta2 |= DMP_Data_Output_Control_2_Gyro_Accuracy; + } + if (((delta & DMP_Data_Output_Control_1_Compass_Calibr) > 0) || ((delta & DMP_Data_Output_Control_1_Compass) > 0) || ((delta & DMP_Data_Output_Control_1_Quat9) > 0) || ((delta & DMP_Data_Output_Control_1_Geomag) > 0)) + { + delta2 |= DMP_Data_Output_Control_2_Compass_Accuracy; + } + // TO DO: Add DMP_Data_Output_Control_2_Pickup etc. if required + + // Write the sensor control bits into memory address DATA_OUT_CTL1 + unsigned char data_output_control_reg[2]; + data_output_control_reg[0] = (unsigned char)(delta >> 8); + data_output_control_reg[1] = (unsigned char)(delta & 0xff); + pdev->_dataOutCtl1 = delta; // Diagnostics + result = inv_icm20948_write_mems(pdev, DATA_OUT_CTL1, 2, (const unsigned char *)&data_output_control_reg); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + // Write the 'header2' sensor control bits into memory address DATA_OUT_CTL2 + data_output_control_reg[0] = (unsigned char)(delta2 >> 8); + data_output_control_reg[1] = (unsigned char)(delta2 & 0xff); + pdev->_dataOutCtl2 = delta2; // Diagnostics + result = inv_icm20948_write_mems(pdev, DATA_OUT_CTL2, 2, (const unsigned char *)&data_output_control_reg); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + // Set the DATA_RDY_STATUS register + data_output_control_reg[0] = (unsigned char)(data_rdy_status >> 8); + data_output_control_reg[1] = (unsigned char)(data_rdy_status & 0xff); + pdev->_dataRdyStatus = data_rdy_status; // Diagnostics + result = inv_icm20948_write_mems(pdev, DATA_RDY_STATUS, 2, (const unsigned char *)&data_output_control_reg); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + // Check which extra bits need to be set in the Motion Event Control register + if ((delta & DMP_Data_Output_Control_1_Quat9) > 0) + { + inv_event_control |= DMP_Motion_Event_Control_9axis; + } + if (((delta & DMP_Data_Output_Control_1_Step_Detector) > 0) || ((delta & DMP_Data_Output_Control_1_Step_Ind_0) > 0) || ((delta & DMP_Data_Output_Control_1_Step_Ind_1) > 0) || ((delta & DMP_Data_Output_Control_1_Step_Ind_2) > 0)) + { + inv_event_control |= DMP_Motion_Event_Control_Pedometer_Interrupt; + } + if ((delta & DMP_Data_Output_Control_1_Geomag) > 0) + { + inv_event_control |= DMP_Motion_Event_Control_Geomag; + } + + // Set the MOTION_EVENT_CTL register + data_output_control_reg[0] = (unsigned char)(inv_event_control >> 8); + data_output_control_reg[1] = (unsigned char)(inv_event_control & 0xff); + pdev->_motionEventCtl = inv_event_control; // Diagnostics + result = inv_icm20948_write_mems(pdev, MOTION_EVENT_CTL, 2, (const unsigned char *)&data_output_control_reg); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + result = ICM_20948_low_power(pdev, true); // Put chip into low power state + if (result != ICM_20948_Stat_Ok) + return result; + + return result; +} + +ICM_20948_Status_e inv_icm20948_enable_dmp_sensor_int(ICM_20948_Device_t *pdev, enum inv_icm20948_sensor sensor, int state) +{ + ICM_20948_Status_e result = ICM_20948_Stat_Ok; + + if (pdev->_dmp_firmware_available == false) + return ICM_20948_Stat_DMPNotSupported; // Bail if DMP is not supported + + uint8_t androidSensor = sensor_type_2_android_sensor(sensor); // Convert sensor from enum inv_icm20948_sensor to Android numbering + + if (androidSensor > ANDROID_SENSOR_NUM_MAX) + return ICM_20948_Stat_SensorNotSupported; // Bail if the sensor is not supported + + // Convert the Android sensor into a bit mask for DATA_OUT_CTL1 + uint16_t delta = inv_androidSensor_to_control_bits[androidSensor]; + if (delta == 0xFFFF) + return ICM_20948_Stat_SensorNotSupported; // Bail if the sensor is not supported + + // Convert the Android sensor number into a bitmask and set or clear that bit in _enabled_Android_intr_0 / _enabled_Android_intr_1 + unsigned long androidSensorAsBitMask; + if (androidSensor < 32) // Sensors 0-31 + { + androidSensorAsBitMask = 1L << androidSensor; + if (state == 0) // Should we disable the sensor interrupt? + { + pdev->_enabled_Android_intr_0 &= ~androidSensorAsBitMask; // Clear the bit to disable the sensor interrupt + } + else + { + pdev->_enabled_Android_intr_0 |= androidSensorAsBitMask; // Set the bit to enable the sensor interrupt + } + } + else // Sensors 32- + { + androidSensorAsBitMask = 1L << (androidSensor - 32); + if (state == 0) // Should we disable the sensor? + { + pdev->_enabled_Android_intr_1 &= ~androidSensorAsBitMask; // Clear the bit to disable the sensor interrupt + } + else + { + pdev->_enabled_Android_intr_1 |= androidSensorAsBitMask; // Set the bit to enable the sensor interrupt + } + } + + // Now we know androidSensor is valid, reconstruct the value for DATA_INTR_CTL from _enabled_Android_intr_0 and _enabled_Android_intr_0 + delta = 0; // Clear delta + for (int i = 0; i < 32; i++) + { + androidSensorAsBitMask = 1L << i; + if ((pdev->_enabled_Android_intr_0 & androidSensorAsBitMask) > 0) // Check if the Android sensor (0-31) interrupt is enabled + { + delta |= inv_androidSensor_to_control_bits[i]; // If it is, or the required bits into delta + } + if ((pdev->_enabled_Android_intr_1 & androidSensorAsBitMask) > 0) // Check if the Android sensor (32-) interrupt is enabled + { + delta |= inv_androidSensor_to_control_bits[i + 32]; // If it is, or the required bits into delta + } + } + + result = ICM_20948_sleep(pdev, false); // Make sure chip is awake + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + result = ICM_20948_low_power(pdev, false); // Make sure chip is not in low power state + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + unsigned char data_intr_ctl[2]; + + data_intr_ctl[0] = (unsigned char)(delta >> 8); + data_intr_ctl[1] = (unsigned char)(delta & 0xff); + pdev->_dataIntrCtl = delta; // Diagnostics + + // Write the interrupt control bits into memory address DATA_INTR_CTL + result = inv_icm20948_write_mems(pdev, DATA_INTR_CTL, 2, (const unsigned char *)&data_intr_ctl); + + result = ICM_20948_low_power(pdev, true); // Put chip into low power state + if (result != ICM_20948_Stat_Ok) + return result; + + return result; +} + +ICM_20948_Status_e inv_icm20948_read_dmp_data(ICM_20948_Device_t *pdev, icm_20948_DMP_data_t *data) +{ + ICM_20948_Status_e result = ICM_20948_Stat_Ok; + uint8_t fifoBytes[icm_20948_DMP_Maximum_Bytes]; // Interim storage for the FIFO data + + if (pdev->_dmp_firmware_available == false) + return ICM_20948_Stat_DMPNotSupported; + + // Check how much data is in the FIFO + uint16_t fifo_count; + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + + if (fifo_count < icm_20948_DMP_Header_Bytes) // Has a 2-byte header arrived? + return ICM_20948_Stat_FIFONoDataAvail; // Bail if no header is available + + // Read the header (2 bytes) + data->header = 0; // Clear the existing header + uint16_t aShort = 0; + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Header_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Header_Bytes; i++) + { + aShort |= ((uint16_t)fifoBytes[i]) << (8 - (i * 8)); // MSB first + } + data->header = aShort; // Store the header in data->header + fifo_count -= icm_20948_DMP_Header_Bytes; // Decrement the count + + // If the header indicates a header2 is present then read that now + data->header2 = 0; // Clear the existing header2 + if ((data->header & DMP_header_bitmap_Header2) > 0) // If the header2 bit is set + { + if (fifo_count < icm_20948_DMP_Header2_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Header2_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if no header2 is available + // Read the header (2 bytes) + aShort = 0; + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Header2_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Header2_Bytes; i++) + { + aShort |= ((uint16_t)fifoBytes[i]) << (8 - (i * 8)); + } + data->header2 = aShort; // Store the header2 in data->header2 + fifo_count -= icm_20948_DMP_Header2_Bytes; // Decrement the count + } + + if ((data->header & DMP_header_bitmap_Accel) > 0) // case DMP_header_bitmap_Accel: + { + if (fifo_count < icm_20948_DMP_Raw_Accel_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Raw_Accel_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Raw_Accel_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Raw_Accel_Bytes; i++) + { + data->Raw_Accel.Bytes[DMP_PQuat6_Byte_Ordering[i]] = fifoBytes[i]; // Correct the byte order (map big endian to little endian) + } + fifo_count -= icm_20948_DMP_Raw_Accel_Bytes; // Decrement the count + } + + if ((data->header & DMP_header_bitmap_Gyro) > 0) // case DMP_header_bitmap_Gyro: + { + if (fifo_count < (icm_20948_DMP_Raw_Gyro_Bytes + icm_20948_DMP_Gyro_Bias_Bytes)) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < (icm_20948_DMP_Raw_Gyro_Bytes + icm_20948_DMP_Gyro_Bias_Bytes)) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], (icm_20948_DMP_Raw_Gyro_Bytes + icm_20948_DMP_Gyro_Bias_Bytes)); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < (icm_20948_DMP_Raw_Gyro_Bytes + icm_20948_DMP_Gyro_Bias_Bytes); i++) + { + data->Raw_Gyro.Bytes[DMP_Raw_Gyro_Byte_Ordering[i]] = fifoBytes[i]; // Correct the byte order (map big endian to little endian) + } + fifo_count -= (icm_20948_DMP_Raw_Gyro_Bytes + icm_20948_DMP_Gyro_Bias_Bytes); // Decrement the count + } + + if ((data->header & DMP_header_bitmap_Compass) > 0) // case DMP_header_bitmap_Compass: + { + if (fifo_count < icm_20948_DMP_Compass_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Compass_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Compass_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Compass_Bytes; i++) + { + data->Compass.Bytes[DMP_PQuat6_Byte_Ordering[i]] = fifoBytes[i]; // Correct the byte order (map big endian to little endian) + } + fifo_count -= icm_20948_DMP_Compass_Bytes; // Decrement the count + } + + if ((data->header & DMP_header_bitmap_ALS) > 0) // case DMP_header_bitmap_ALS: + { + if (fifo_count < icm_20948_DMP_ALS_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_ALS_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_ALS_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_ALS_Bytes; i++) + { + data->ALS[i] = fifoBytes[i]; + } + fifo_count -= icm_20948_DMP_ALS_Bytes; // Decrement the count + } + + if ((data->header & DMP_header_bitmap_Quat6) > 0) // case DMP_header_bitmap_Quat6: + { + if (fifo_count < icm_20948_DMP_Quat6_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Quat6_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Quat6_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Quat6_Bytes; i++) + { + data->Quat6.Bytes[DMP_Quat6_Byte_Ordering[i]] = fifoBytes[i]; // Correct the byte order (map big endian to little endian) + } + fifo_count -= icm_20948_DMP_Quat6_Bytes; // Decrement the count + } + + if ((data->header & DMP_header_bitmap_Quat9) > 0) // case DMP_header_bitmap_Quat9: + { + if (fifo_count < icm_20948_DMP_Quat9_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Quat9_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Quat9_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Quat9_Bytes; i++) + { + data->Quat9.Bytes[DMP_Quat9_Byte_Ordering[i]] = fifoBytes[i]; // Correct the byte order (map big endian to little endian) + } + fifo_count -= icm_20948_DMP_Quat9_Bytes; // Decrement the count + } + + if ((data->header & DMP_header_bitmap_PQuat6) > 0) // case DMP_header_bitmap_PQuat6: + { + if (fifo_count < icm_20948_DMP_PQuat6_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_PQuat6_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_PQuat6_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_PQuat6_Bytes; i++) + { + data->PQuat6.Bytes[DMP_PQuat6_Byte_Ordering[i]] = fifoBytes[i]; // Correct the byte order (map big endian to little endian) + } + fifo_count -= icm_20948_DMP_PQuat6_Bytes; // Decrement the count + } + + if ((data->header & DMP_header_bitmap_Geomag) > 0) // case DMP_header_bitmap_Geomag: + { + if (fifo_count < icm_20948_DMP_Geomag_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Geomag_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Geomag_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Geomag_Bytes; i++) + { + data->Geomag.Bytes[DMP_Quat9_Byte_Ordering[i]] = fifoBytes[i]; // Correct the byte order (map big endian to little endian) + } + fifo_count -= icm_20948_DMP_Geomag_Bytes; // Decrement the count + } + + if ((data->header & DMP_header_bitmap_Pressure) > 0) // case DMP_header_bitmap_Pressure: + { + if (fifo_count < icm_20948_DMP_Pressure_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Pressure_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Pressure_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Pressure_Bytes; i++) + { + data->Pressure[i] = fifoBytes[i]; + } + fifo_count -= icm_20948_DMP_Pressure_Bytes; // Decrement the count + } + + if ((data->header & DMP_header_bitmap_Gyro_Calibr) > 0) // case DMP_header_bitmap_Gyro_Calibr: + { + // lcm20948MPUFifoControl.c suggests icm_20948_DMP_Gyro_Calibr_Bytes is not supported + // and looking at DMP frames which have the Gyro_Calibr bit set, that certainly seems to be true. + // So, we'll skip this...: + /* + if (fifo_count < icm_20948_DMP_Gyro_Calibr_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Gyro_Calibr_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Gyro_Calibr_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Gyro_Calibr_Bytes; i++) + { + data->Gyro_Calibr.Bytes[DMP_Quat6_Byte_Ordering[i]] = fifoBytes[i]; // Correct the byte order (map big endian to little endian) + } + fifo_count -= icm_20948_DMP_Gyro_Calibr_Bytes; // Decrement the count + */ + } + + if ((data->header & DMP_header_bitmap_Compass_Calibr) > 0) // case DMP_header_bitmap_Compass_Calibr: + { + if (fifo_count < icm_20948_DMP_Compass_Calibr_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Compass_Calibr_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Compass_Calibr_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Compass_Calibr_Bytes; i++) + { + data->Compass_Calibr.Bytes[DMP_Quat6_Byte_Ordering[i]] = fifoBytes[i]; // Correct the byte order (map big endian to little endian) + } + fifo_count -= icm_20948_DMP_Compass_Calibr_Bytes; // Decrement the count + } + + if ((data->header & DMP_header_bitmap_Step_Detector) > 0) // case DMP_header_bitmap_Step_Detector: + { + if (fifo_count < icm_20948_DMP_Step_Detector_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Step_Detector_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Step_Detector_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + uint32_t aWord = 0; + for (int i = 0; i < icm_20948_DMP_Step_Detector_Bytes; i++) + { + aWord |= ((uint32_t)fifoBytes[i]) << (24 - (i * 8)); // MSB first + } + data->Pedometer_Timestamp = aWord; + fifo_count -= icm_20948_DMP_Step_Detector_Bytes; // Decrement the count + } + + // Now check for header2 features + + if ((data->header2 & DMP_header2_bitmap_Accel_Accuracy) > 0) // case DMP_header2_bitmap_Accel_Accuracy: + { + if (fifo_count < icm_20948_DMP_Accel_Accuracy_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Accel_Accuracy_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + aShort = 0; + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Accel_Accuracy_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Accel_Accuracy_Bytes; i++) + { + aShort |= ((uint16_t)fifoBytes[i]) << (8 - (i * 8)); + } + data->Accel_Accuracy = aShort; + fifo_count -= icm_20948_DMP_Accel_Accuracy_Bytes; // Decrement the count + } + + if ((data->header2 & DMP_header2_bitmap_Gyro_Accuracy) > 0) // case DMP_header2_bitmap_Gyro_Accuracy: + { + if (fifo_count < icm_20948_DMP_Gyro_Accuracy_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Gyro_Accuracy_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + aShort = 0; + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Gyro_Accuracy_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Gyro_Accuracy_Bytes; i++) + { + aShort |= ((uint16_t)fifoBytes[i]) << (8 - (i * 8)); + } + data->Gyro_Accuracy = aShort; + fifo_count -= icm_20948_DMP_Gyro_Accuracy_Bytes; // Decrement the count + } + + if ((data->header2 & DMP_header2_bitmap_Compass_Accuracy) > 0) // case DMP_header2_bitmap_Compass_Accuracy: + { + if (fifo_count < icm_20948_DMP_Compass_Accuracy_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Compass_Accuracy_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + aShort = 0; + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Compass_Accuracy_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Compass_Accuracy_Bytes; i++) + { + aShort |= ((uint16_t)fifoBytes[i]) << (8 - (i * 8)); + } + data->Compass_Accuracy = aShort; + fifo_count -= icm_20948_DMP_Compass_Accuracy_Bytes; // Decrement the count + } + + if ((data->header2 & DMP_header2_bitmap_Fsync) > 0) // case DMP_header2_bitmap_Fsync: + { + // lcm20948MPUFifoControl.c suggests icm_20948_DMP_Fsync_Detection_Bytes is not supported. + // So, we'll skip this just in case...: + /* + if (fifo_count < icm_20948_DMP_Fsync_Detection_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Fsync_Detection_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + aShort = 0; + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Fsync_Detection_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Fsync_Detection_Bytes; i++) + { + aShort |= ((uint16_t)fifoBytes[i]) << (8 - (i * 8)); + } + data->Fsync_Delay_Time = aShort; + fifo_count -= icm_20948_DMP_Fsync_Detection_Bytes; // Decrement the count + */ + } + + if ((data->header2 & DMP_header2_bitmap_Pickup) > 0) // case DMP_header2_bitmap_Pickup: + { + if (fifo_count < icm_20948_DMP_Pickup_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Pickup_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + aShort = 0; + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Pickup_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Pickup_Bytes; i++) + { + aShort |= ((uint16_t)fifoBytes[i]) << (8 - (i * 8)); + } + data->Pickup = aShort; + fifo_count -= icm_20948_DMP_Pickup_Bytes; // Decrement the count + } + + if ((data->header2 & DMP_header2_bitmap_Activity_Recog) > 0) // case DMP_header2_bitmap_Activity_Recog: + { + if (fifo_count < icm_20948_DMP_Activity_Recognition_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Activity_Recognition_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Activity_Recognition_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Activity_Recognition_Bytes; i++) + { + data->Activity_Recognition.Bytes[DMP_Activity_Recognition_Byte_Ordering[i]] = fifoBytes[i]; + } + fifo_count -= icm_20948_DMP_Activity_Recognition_Bytes; // Decrement the count + } + + if ((data->header2 & DMP_header2_bitmap_Secondary_On_Off) > 0) // case DMP_header2_bitmap_Secondary_On_Off: + { + if (fifo_count < icm_20948_DMP_Secondary_On_Off_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Secondary_On_Off_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Secondary_On_Off_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Secondary_On_Off_Bytes; i++) + { + data->Secondary_On_Off.Bytes[DMP_Secondary_On_Off_Byte_Ordering[i]] = fifoBytes[i]; + } + fifo_count -= icm_20948_DMP_Secondary_On_Off_Bytes; // Decrement the count + } + + // Finally, extract the footer (gyro count) + if (fifo_count < icm_20948_DMP_Footer_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Footer_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + aShort = 0; + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Footer_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Footer_Bytes; i++) + { + aShort |= ((uint16_t)fifoBytes[i]) << (8 - (i * 8)); + } + data->Footer = aShort; + fifo_count -= icm_20948_DMP_Footer_Bytes; // Decrement the count + + if (fifo_count > 0) // Check if there is still data waiting to be read + return ICM_20948_Stat_FIFOMoreDataAvail; + + return result; +} + +uint8_t sensor_type_2_android_sensor(enum inv_icm20948_sensor sensor) +{ + switch (sensor) + { + case INV_ICM20948_SENSOR_ACCELEROMETER: + return ANDROID_SENSOR_ACCELEROMETER; // 1 + case INV_ICM20948_SENSOR_GYROSCOPE: + return ANDROID_SENSOR_GYROSCOPE; // 4 + case INV_ICM20948_SENSOR_RAW_ACCELEROMETER: + return ANDROID_SENSOR_RAW_ACCELEROMETER; // 42 + case INV_ICM20948_SENSOR_RAW_GYROSCOPE: + return ANDROID_SENSOR_RAW_GYROSCOPE; // 43 + case INV_ICM20948_SENSOR_MAGNETIC_FIELD_UNCALIBRATED: + return ANDROID_SENSOR_MAGNETIC_FIELD_UNCALIBRATED; // 14 + case INV_ICM20948_SENSOR_GYROSCOPE_UNCALIBRATED: + return ANDROID_SENSOR_GYROSCOPE_UNCALIBRATED; // 16 + case INV_ICM20948_SENSOR_ACTIVITY_CLASSIFICATON: + return ANDROID_SENSOR_ACTIVITY_CLASSIFICATON; // 47 + case INV_ICM20948_SENSOR_STEP_DETECTOR: + return ANDROID_SENSOR_STEP_DETECTOR; // 18 + case INV_ICM20948_SENSOR_STEP_COUNTER: + return ANDROID_SENSOR_STEP_COUNTER; // 19 + case INV_ICM20948_SENSOR_GAME_ROTATION_VECTOR: + return ANDROID_SENSOR_GAME_ROTATION_VECTOR; // 15 + case INV_ICM20948_SENSOR_ROTATION_VECTOR: + return ANDROID_SENSOR_ROTATION_VECTOR; // 11 + case INV_ICM20948_SENSOR_GEOMAGNETIC_ROTATION_VECTOR: + return ANDROID_SENSOR_GEOMAGNETIC_ROTATION_VECTOR; // 20 + case INV_ICM20948_SENSOR_GEOMAGNETIC_FIELD: + return ANDROID_SENSOR_GEOMAGNETIC_FIELD; // 2 + case INV_ICM20948_SENSOR_WAKEUP_SIGNIFICANT_MOTION: + return ANDROID_SENSOR_WAKEUP_SIGNIFICANT_MOTION; // 17 + case INV_ICM20948_SENSOR_FLIP_PICKUP: + return ANDROID_SENSOR_FLIP_PICKUP; // 46 + case INV_ICM20948_SENSOR_WAKEUP_TILT_DETECTOR: + return ANDROID_SENSOR_WAKEUP_TILT_DETECTOR; // 41 + case INV_ICM20948_SENSOR_GRAVITY: + return ANDROID_SENSOR_GRAVITY; // 9 + case INV_ICM20948_SENSOR_LINEAR_ACCELERATION: + return ANDROID_SENSOR_LINEAR_ACCELERATION; // 10 + case INV_ICM20948_SENSOR_ORIENTATION: + return ANDROID_SENSOR_ORIENTATION; // 3 + case INV_ICM20948_SENSOR_B2S: + return ANDROID_SENSOR_B2S; // 45 + default: + return ANDROID_SENSOR_NUM_MAX; + } +} + +enum inv_icm20948_sensor inv_icm20948_sensor_android_2_sensor_type(int sensor) +{ + switch (sensor) + { + case ANDROID_SENSOR_ACCELEROMETER: + return INV_ICM20948_SENSOR_ACCELEROMETER; + case ANDROID_SENSOR_GYROSCOPE: + return INV_ICM20948_SENSOR_GYROSCOPE; + case ANDROID_SENSOR_RAW_ACCELEROMETER: + return INV_ICM20948_SENSOR_RAW_ACCELEROMETER; + case ANDROID_SENSOR_RAW_GYROSCOPE: + return INV_ICM20948_SENSOR_RAW_GYROSCOPE; + case ANDROID_SENSOR_MAGNETIC_FIELD_UNCALIBRATED: + return INV_ICM20948_SENSOR_MAGNETIC_FIELD_UNCALIBRATED; + case ANDROID_SENSOR_GYROSCOPE_UNCALIBRATED: + return INV_ICM20948_SENSOR_GYROSCOPE_UNCALIBRATED; + case ANDROID_SENSOR_ACTIVITY_CLASSIFICATON: + return INV_ICM20948_SENSOR_ACTIVITY_CLASSIFICATON; + case ANDROID_SENSOR_STEP_DETECTOR: + return INV_ICM20948_SENSOR_STEP_DETECTOR; + case ANDROID_SENSOR_STEP_COUNTER: + return INV_ICM20948_SENSOR_STEP_COUNTER; + case ANDROID_SENSOR_GAME_ROTATION_VECTOR: + return INV_ICM20948_SENSOR_GAME_ROTATION_VECTOR; + case ANDROID_SENSOR_ROTATION_VECTOR: + return INV_ICM20948_SENSOR_ROTATION_VECTOR; + case ANDROID_SENSOR_GEOMAGNETIC_ROTATION_VECTOR: + return INV_ICM20948_SENSOR_GEOMAGNETIC_ROTATION_VECTOR; + case ANDROID_SENSOR_GEOMAGNETIC_FIELD: + return INV_ICM20948_SENSOR_GEOMAGNETIC_FIELD; + case ANDROID_SENSOR_WAKEUP_SIGNIFICANT_MOTION: + return INV_ICM20948_SENSOR_WAKEUP_SIGNIFICANT_MOTION; + case ANDROID_SENSOR_FLIP_PICKUP: + return INV_ICM20948_SENSOR_FLIP_PICKUP; + case ANDROID_SENSOR_WAKEUP_TILT_DETECTOR: + return INV_ICM20948_SENSOR_WAKEUP_TILT_DETECTOR; + case ANDROID_SENSOR_GRAVITY: + return INV_ICM20948_SENSOR_GRAVITY; + case ANDROID_SENSOR_LINEAR_ACCELERATION: + return INV_ICM20948_SENSOR_LINEAR_ACCELERATION; + case ANDROID_SENSOR_ORIENTATION: + return INV_ICM20948_SENSOR_ORIENTATION; + case ANDROID_SENSOR_B2S: + return INV_ICM20948_SENSOR_B2S; + default: + return INV_ICM20948_SENSOR_MAX; + } +} + +ICM_20948_Status_e inv_icm20948_set_gyro_sf(ICM_20948_Device_t *pdev, unsigned char div, int gyro_level) +{ + ICM_20948_Status_e result = ICM_20948_Stat_Ok; + + if (pdev->_dmp_firmware_available == false) + return ICM_20948_Stat_DMPNotSupported; + + // gyro_level should be set to 4 regardless of fullscale, due to the addition of API dmp_icm20648_set_gyro_fsr() + gyro_level = 4; + + // First read the TIMEBASE_CORRECTION_PLL register from Bank 1 + int8_t pll; // Signed. Typical value is 0x18 + result = ICM_20948_set_bank(pdev, 1); + result = ICM_20948_execute_r(pdev, AGB1_REG_TIMEBASE_CORRECTION_PLL, (uint8_t *)&pll, 1); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + pdev->_gyroSFpll = pll; // Record the PLL value so we can debug print it + + // Now calculate the Gyro SF using code taken from the InvenSense example (inv_icm20948_set_gyro_sf) + + long gyro_sf; + + unsigned long long const MagicConstant = 264446880937391LL; + unsigned long long const MagicConstantScale = 100000LL; + unsigned long long ResultLL; + + if (pll & 0x80) + { + ResultLL = (MagicConstant * (long long)(1ULL << gyro_level) * (1 + div) / (1270 - (pll & 0x7F)) / MagicConstantScale); + } + else + { + ResultLL = (MagicConstant * (long long)(1ULL << gyro_level) * (1 + div) / (1270 + pll) / MagicConstantScale); + } + /* + In above deprecated FP version, worst case arguments can produce a result that overflows a signed long. + Here, for such cases, we emulate the FP behavior of setting the result to the maximum positive value, as + the compiler's conversion of a u64 to an s32 is simple truncation of the u64's high half, sadly.... + */ + if (ResultLL > 0x7FFFFFFF) + gyro_sf = 0x7FFFFFFF; + else + gyro_sf = (long)ResultLL; + + pdev->_gyroSF = gyro_sf; // Record value so we can debug print it + + // Finally, write the value to the DMP GYRO_SF register + unsigned char gyro_sf_reg[4]; + gyro_sf_reg[0] = (unsigned char)(gyro_sf >> 24); + gyro_sf_reg[1] = (unsigned char)(gyro_sf >> 16); + gyro_sf_reg[2] = (unsigned char)(gyro_sf >> 8); + gyro_sf_reg[3] = (unsigned char)(gyro_sf & 0xff); + result = inv_icm20948_write_mems(pdev, GYRO_SF, 4, (const unsigned char*)&gyro_sf_reg); + + return result; +} + + diff --git a/src/util/ICM_20948_C.h b/src/util/ICM_20948_C.h new file mode 100644 index 0000000..934f8d3 --- /dev/null +++ b/src/util/ICM_20948_C.h @@ -0,0 +1,303 @@ +/* + +This is a C-compatible interface to the features presented by the ICM 20948 9-axis device +The imementation of the interface is flexible + +*/ + +#ifndef _ICM_20948_C_H_ +#define _ICM_20948_C_H_ + +#include +#include +#include + +#include "ICM_20948_REGISTERS.h" +#include "ICM_20948_ENUMERATIONS.h" // This is to give users access to usable value definiitons +#include "AK09916_ENUMERATIONS.h" +#include "ICM_20948_DMP.h" + +#ifdef __cplusplus +extern "C" +{ +#endif /* __cplusplus */ + +extern int memcmp(const void *, const void *, size_t); // Avoid compiler warnings + +// Define if the DMP will be supported +// Note: you must have 14290/14301 Bytes of program memory available to store the DMP firmware! +//#define ICM_20948_USE_DMP // Uncomment this line to enable DMP support. You can of course use ICM_20948_USE_DMP as a compiler flag too + +// There are two versions of the InvenSense DMP firmware for the ICM20948 - with slightly different sizes +#define DMP_CODE_SIZE 14301 /* eMD-SmartMotion-ICM20948-1.1.0-MP */ +//#define DMP_CODE_SIZE 14290 /* ICM20948_eMD_nucleo_1.0 */ + + +#define ICM_20948_I2C_ADDR_AD0 0x68 // Or 0x69 when AD0 is high +#define ICM_20948_I2C_ADDR_AD1 0x69 // +#define ICM_20948_WHOAMI 0xEA + +#define MAG_AK09916_I2C_ADDR 0x0C +#define MAG_AK09916_WHO_AM_I 0x4809 +#define MAG_REG_WHO_AM_I 0x00 + +/** @brief Max size that can be read across I2C or SPI data lines */ +#define INV_MAX_SERIAL_READ 16 +/** @brief Max size that can be written across I2C or SPI data lines */ +#define INV_MAX_SERIAL_WRITE 16 + + typedef enum + { + ICM_20948_Stat_Ok = 0x00, // The only return code that means all is well + ICM_20948_Stat_Err, // A general error + ICM_20948_Stat_NotImpl, // Returned by virtual functions that are not implemented + ICM_20948_Stat_ParamErr, + ICM_20948_Stat_WrongID, + ICM_20948_Stat_InvalSensor, // Tried to apply a function to a sensor that does not support it (e.g. DLPF to the temperature sensor) + ICM_20948_Stat_NoData, + ICM_20948_Stat_SensorNotSupported, + ICM_20948_Stat_DMPNotSupported, // DMP not supported (no #define ICM_20948_USE_DMP) + ICM_20948_Stat_DMPVerifyFail, // DMP was written but did not verify correctly + ICM_20948_Stat_FIFONoDataAvail, // FIFO contains no data + ICM_20948_Stat_FIFOIncompleteData, // FIFO contained incomplete data + ICM_20948_Stat_FIFOMoreDataAvail, // FIFO contains more data + ICM_20948_Stat_UnrecognisedDMPHeader, + ICM_20948_Stat_UnrecognisedDMPHeader2, + ICM_20948_Stat_InvalDMPRegister, // Invalid DMP Register + + ICM_20948_Stat_NUM, + ICM_20948_Stat_Unknown, + } ICM_20948_Status_e; + + typedef enum + { + ICM_20948_Internal_Acc = (1 << 0), + ICM_20948_Internal_Gyr = (1 << 1), + ICM_20948_Internal_Mag = (1 << 2), + ICM_20948_Internal_Tmp = (1 << 3), + ICM_20948_Internal_Mst = (1 << 4), // I2C Master Ineternal + } ICM_20948_InternalSensorID_bm; // A bitmask of internal sensor IDs + + typedef union + { + int16_t i16bit[3]; + uint8_t u8bit[6]; + } ICM_20948_axis3bit16_t; + + typedef union + { + int16_t i16bit; + uint8_t u8bit[2]; + } ICM_20948_axis1bit16_t; + + typedef struct + { + uint8_t a : 2; + uint8_t g : 2; + uint8_t reserved_0 : 4; + } ICM_20948_fss_t; // Holds full-scale settings to be able to extract measurements with units + + typedef struct + { + uint8_t a; + uint8_t g; + } ICM_20948_dlpcfg_t; // Holds digital low pass filter settings. Members are type ICM_20948_ACCEL_CONFIG_DLPCFG_e + + typedef struct + { + uint16_t a; + uint8_t g; + } ICM_20948_smplrt_t; + + typedef struct + { + uint8_t I2C_MST_INT_EN : 1; + uint8_t DMP_INT1_EN : 1; + uint8_t PLL_RDY_EN : 1; + uint8_t WOM_INT_EN : 1; + uint8_t REG_WOF_EN : 1; + uint8_t RAW_DATA_0_RDY_EN : 1; + uint8_t FIFO_OVERFLOW_EN_4 : 1; + uint8_t FIFO_OVERFLOW_EN_3 : 1; + uint8_t FIFO_OVERFLOW_EN_2 : 1; + uint8_t FIFO_OVERFLOW_EN_1 : 1; + uint8_t FIFO_OVERFLOW_EN_0 : 1; + uint8_t FIFO_WM_EN_4 : 1; + uint8_t FIFO_WM_EN_3 : 1; + uint8_t FIFO_WM_EN_2 : 1; + uint8_t FIFO_WM_EN_1 : 1; + uint8_t FIFO_WM_EN_0 : 1; + } ICM_20948_INT_enable_t; + + typedef union + { + ICM_20948_axis3bit16_t raw; + struct + { + int16_t x; + int16_t y; + int16_t z; + } axes; + } ICM_20948_axis3named_t; + + typedef struct + { + ICM_20948_axis3named_t acc; + ICM_20948_axis3named_t gyr; + ICM_20948_axis3named_t mag; + union + { + ICM_20948_axis1bit16_t raw; + int16_t val; + } tmp; + ICM_20948_fss_t fss; // Full-scale range settings for this measurement + uint8_t magStat1; + uint8_t magStat2; + } ICM_20948_AGMT_t; + + typedef struct + { + ICM_20948_Status_e (*write)(uint8_t regaddr, uint8_t *pdata, uint32_t len, void *user); + ICM_20948_Status_e (*read)(uint8_t regaddr, uint8_t *pdata, uint32_t len, void *user); + // void (*delay)(uint32_t ms); + void *user; + } ICM_20948_Serif_t; // This is the vtable of serial interface functions + extern const ICM_20948_Serif_t NullSerif; // Here is a default for initialization (NULL) + + typedef struct + { + const ICM_20948_Serif_t *_serif; // Pointer to the assigned Serif (Serial Interface) vtable + bool _dmp_firmware_available; // Indicates if the DMP firmware has been included. It + bool _firmware_loaded; // Indicates if DMP has been loaded + uint8_t _last_bank; // Keep track of which bank was selected last - to avoid unnecessary writes + uint8_t _last_mems_bank; // Keep track of which bank was selected last - to avoid unnecessary writes + int32_t _gyroSF; // Use this to record the GyroSF, calculated by inv_icm20948_set_gyro_sf + int8_t _gyroSFpll; + uint32_t _enabled_Android_0; // Keep track of which Android sensors are enabled: 0-31 + uint32_t _enabled_Android_1; // Keep track of which Android sensors are enabled: 32- + uint32_t _enabled_Android_intr_0; // Keep track of which Android sensor interrupts are enabled: 0-31 + uint32_t _enabled_Android_intr_1; // Keep track of which Android sensor interrupts are enabled: 32- + uint16_t _dataOutCtl1; // Diagnostics: record the setting of DATA_OUT_CTL1 + uint16_t _dataOutCtl2; // Diagnostics: record the setting of DATA_OUT_CTL2 + uint16_t _dataRdyStatus; // Diagnostics: record the setting of DATA_RDY_STATUS + uint16_t _motionEventCtl; // Diagnostics: record the setting of MOTION_EVENT_CTL + uint16_t _dataIntrCtl; // Diagnostics: record the setting of DATA_INTR_CTL + } ICM_20948_Device_t; // Definition of device struct type + + ICM_20948_Status_e ICM_20948_init_struct(ICM_20948_Device_t *pdev); // Initialize ICM_20948_Device_t + + // ICM_20948_Status_e ICM_20948_Startup( ICM_20948_Device_t* pdev ); // For the time being this performs a standardized startup routine + + ICM_20948_Status_e ICM_20948_link_serif(ICM_20948_Device_t *pdev, const ICM_20948_Serif_t *s); // Links a SERIF structure to the device + + // use the device's serif to perform a read or write + ICM_20948_Status_e ICM_20948_execute_r(ICM_20948_Device_t *pdev, uint8_t regaddr, uint8_t *pdata, uint32_t len); // Executes a R or W witht he serif vt as long as the pointers are not null + ICM_20948_Status_e ICM_20948_execute_w(ICM_20948_Device_t *pdev, uint8_t regaddr, uint8_t *pdata, uint32_t len); + + // Single-shot I2C on Master IF + ICM_20948_Status_e ICM_20948_i2c_controller_periph4_txn(ICM_20948_Device_t *pdev, uint8_t addr, uint8_t reg, uint8_t *data, uint8_t len, bool Rw, bool send_reg_addr); + ICM_20948_Status_e ICM_20948_i2c_master_single_w(ICM_20948_Device_t *pdev, uint8_t addr, uint8_t reg, uint8_t *data); + ICM_20948_Status_e ICM_20948_i2c_master_single_r(ICM_20948_Device_t *pdev, uint8_t addr, uint8_t reg, uint8_t *data); + + // Device Level + ICM_20948_Status_e ICM_20948_set_bank(ICM_20948_Device_t *pdev, uint8_t bank); // Sets the bank + ICM_20948_Status_e ICM_20948_sw_reset(ICM_20948_Device_t *pdev); // Performs a SW reset + ICM_20948_Status_e ICM_20948_sleep(ICM_20948_Device_t *pdev, bool on); // Set sleep mode for the chip + ICM_20948_Status_e ICM_20948_low_power(ICM_20948_Device_t *pdev, bool on); // Set low power mode for the chip + ICM_20948_Status_e ICM_20948_set_clock_source(ICM_20948_Device_t *pdev, ICM_20948_PWR_MGMT_1_CLKSEL_e source); // Choose clock source + ICM_20948_Status_e ICM_20948_get_who_am_i(ICM_20948_Device_t *pdev, uint8_t *whoami); // Return whoami in out prarmeter + ICM_20948_Status_e ICM_20948_check_id(ICM_20948_Device_t *pdev); // Return 'ICM_20948_Stat_Ok' if whoami matches ICM_20948_WHOAMI + ICM_20948_Status_e ICM_20948_data_ready(ICM_20948_Device_t *pdev); // Returns 'Ok' if data is ready + + // Interrupt Configuration + ICM_20948_Status_e ICM_20948_int_pin_cfg(ICM_20948_Device_t *pdev, ICM_20948_INT_PIN_CFG_t *write, ICM_20948_INT_PIN_CFG_t *read); // Set the INT pin configuration + ICM_20948_Status_e ICM_20948_int_enable(ICM_20948_Device_t *pdev, ICM_20948_INT_enable_t *write, ICM_20948_INT_enable_t *read); // Write and or read the interrupt enable information. If non-null the write operation occurs before the read, so as to verify that the write was successful + + // WoM Threshold Level Configuration + ICM_20948_Status_e ICM_20948_wom_threshold(ICM_20948_Device_t *pdev, ICM_20948_ACCEL_WOM_THR_t *write, ICM_20948_ACCEL_WOM_THR_t *read); // Write and or read the Wake on Motion threshold. If non-null the write operation occurs before the read, so as to verify that the write was successful + + // Internal Sensor Options + ICM_20948_Status_e ICM_20948_set_sample_mode(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, ICM_20948_LP_CONFIG_CYCLE_e mode); // Use to set accel, gyro, and I2C master into cycled or continuous modes + ICM_20948_Status_e ICM_20948_set_full_scale(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, ICM_20948_fss_t fss); + ICM_20948_Status_e ICM_20948_set_dlpf_cfg(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, ICM_20948_dlpcfg_t cfg); + ICM_20948_Status_e ICM_20948_enable_dlpf(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, bool enable); + ICM_20948_Status_e ICM_20948_set_sample_rate(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, ICM_20948_smplrt_t smplrt); + + // Interface Things + ICM_20948_Status_e ICM_20948_i2c_master_passthrough(ICM_20948_Device_t *pdev, bool passthrough); + ICM_20948_Status_e ICM_20948_i2c_master_enable(ICM_20948_Device_t *pdev, bool enable); + ICM_20948_Status_e ICM_20948_i2c_master_reset(ICM_20948_Device_t *pdev); + ICM_20948_Status_e ICM_20948_i2c_controller_configure_peripheral(ICM_20948_Device_t *pdev, uint8_t peripheral, uint8_t addr, uint8_t reg, uint8_t len, bool Rw, bool enable, bool data_only, bool grp, bool swap, uint8_t dataOut); + + // Higher Level + ICM_20948_Status_e ICM_20948_get_agmt(ICM_20948_Device_t *pdev, ICM_20948_AGMT_t *p); + + // FIFO + + ICM_20948_Status_e ICM_20948_enable_FIFO(ICM_20948_Device_t *pdev, bool enable); + ICM_20948_Status_e ICM_20948_reset_FIFO(ICM_20948_Device_t *pdev); + ICM_20948_Status_e ICM_20948_set_FIFO_mode(ICM_20948_Device_t *pdev, bool snapshot); + ICM_20948_Status_e ICM_20948_get_FIFO_count(ICM_20948_Device_t *pdev, uint16_t *count); + ICM_20948_Status_e ICM_20948_read_FIFO(ICM_20948_Device_t *pdev, uint8_t *data, uint8_t len); + + // DMP + + ICM_20948_Status_e ICM_20948_enable_DMP(ICM_20948_Device_t *pdev, bool enable); + ICM_20948_Status_e ICM_20948_reset_DMP(ICM_20948_Device_t *pdev); + ICM_20948_Status_e ICM_20948_firmware_load(ICM_20948_Device_t *pdev); + ICM_20948_Status_e ICM_20948_set_dmp_start_address(ICM_20948_Device_t *pdev, unsigned short address); + + /** @brief Loads the DMP firmware from SRAM + * @param[in] data pointer where the image + * @param[in] size size if the image + * @param[in] load_addr address to loading the image + * @return 0 in case of success, -1 for any error + */ + ICM_20948_Status_e inv_icm20948_firmware_load(ICM_20948_Device_t *pdev, const unsigned char *data, unsigned short size, unsigned short load_addr); + /** + * @brief Write data to a register in DMP memory + * @param[in] DMP memory address + * @param[in] number of byte to be written + * @param[out] output data from the register + * @return 0 if successful. + */ + ICM_20948_Status_e inv_icm20948_write_mems(ICM_20948_Device_t *pdev, unsigned short reg, unsigned int length, const unsigned char *data); + /** + * @brief Read data from a register in DMP memory + * @param[in] DMP memory address + * @param[in] number of byte to be read + * @param[in] input data from the register + * @return 0 if successful. + */ + ICM_20948_Status_e inv_icm20948_read_mems(ICM_20948_Device_t *pdev, unsigned short reg, unsigned int length, unsigned char *data); + + ICM_20948_Status_e inv_icm20948_set_dmp_sensor_period(ICM_20948_Device_t *pdev, enum DMP_ODR_Registers odr_reg, uint16_t interval); + ICM_20948_Status_e inv_icm20948_enable_dmp_sensor(ICM_20948_Device_t *pdev, enum inv_icm20948_sensor sensor, int state); // State is actually boolean + ICM_20948_Status_e inv_icm20948_enable_dmp_sensor_int(ICM_20948_Device_t *pdev, enum inv_icm20948_sensor sensor, int state); // State is actually boolean + uint8_t sensor_type_2_android_sensor(enum inv_icm20948_sensor sensor); + enum inv_icm20948_sensor inv_icm20948_sensor_android_2_sensor_type(int sensor); + + ICM_20948_Status_e inv_icm20948_read_dmp_data(ICM_20948_Device_t *pdev, icm_20948_DMP_data_t *data); + ICM_20948_Status_e inv_icm20948_set_gyro_sf(ICM_20948_Device_t *pdev, unsigned char div, int gyro_level); + + // ToDo: + + /* + Want to access magnetometer throught the I2C master interface... + + // If using the I2C master to read from the magnetometer + // Enable the I2C master to talk to the magnetometer through the ICM 20948 + myICM.i2cMasterEnable( true ); + SERIAL_PORT.print(F("Enabling the I2C master returned ")); SERIAL_PORT.println(myICM.statusString()); + myICM.i2cControllerConfigurePeripheral ( 0, MAG_AK09916_I2C_ADDR, REG_ST1, 9, true, true, false, false, false ); + SERIAL_PORT.print(F("Configuring the magnetometer peripheral returned ")); SERIAL_PORT.println(myICM.statusString()); + + // Operate the I2C master in duty-cycled mode + myICM.setSampleMode( (ICM_20948_Internal_Mst | ICM_20948_Internal_Gyr), ICM_20948_Sample_Mode_Cycled ); // options: ICM_20948_Sample_Mode_Continuous or ICM_20948_Sample_Mode_Cycled +*/ + +#ifdef __cplusplus +} +#endif /* __cplusplus */ + +#endif /* _ICM_20948_C_H_ */ diff --git a/src/util/ICM_20948_DMP.h b/src/util/ICM_20948_DMP.h new file mode 100644 index 0000000..2354016 --- /dev/null +++ b/src/util/ICM_20948_DMP.h @@ -0,0 +1,695 @@ +/* + +This file contains a useful c translation of the DMP register map + +*/ + +#ifndef _ICM_20948_DMP_H_ +#define _ICM_20948_DMP_H_ + +#include + +#ifdef __cplusplus +extern "C" +{ +#endif /* __cplusplus */ + +#define DMP_START_ADDRESS ((unsigned short)0x1000) +#define DMP_MEM_BANK_SIZE 256 +#define DMP_LOAD_START 0x90 + +#define CFG_FIFO_SIZE (4222) + +// AGB0_REG_DMP_INT_STATUS bit definitions +#define BIT_WAKE_ON_MOTION_INT 0x08 +#define BIT_MSG_DMP_INT 0x0002 +#define BIT_MSG_DMP_INT_0 0x0100 // CI Command + +#define BIT_MSG_DMP_INT_2 0x0200 // CIM Command - SMD +#define BIT_MSG_DMP_INT_3 0x0400 // CIM Command - Pedometer + +#define BIT_MSG_DMP_INT_4 0x1000 // CIM Command - Pedometer binning +#define BIT_MSG_DMP_INT_5 0x2000 // CIM Command - Bring To See Gesture +#define BIT_MSG_DMP_INT_6 0x4000 // CIM Command - Look To See Gesture + +// Appendix I: DMP register addresses + +// data output control +#define DATA_OUT_CTL1 (4 * 16) // 16-bit: Data output control 1 register : configure DMP to output required data +#define DATA_OUT_CTL2 (4 * 16 + 2) // 16-bit: Data output control 2 register : configure the BM, accel/gyro/compass accuracy and gesture such as Pick-up +#define DATA_INTR_CTL (4 * 16 + 12) // 16-bit: Determines which sensors can generate interrupt according to bit map defined for DATA_OUT_CTL1 +#define FIFO_WATERMARK (31 * 16 + 14) // 16-bit: DMP will send FIFO interrupt if FIFO count > FIFO watermark. FIFO watermark is set to 80% of actual FIFO size by default + +// motion event control +#define MOTION_EVENT_CTL (4 * 16 + 14) // 16-bit: configure DMP for Android L and Invensense specific features + +// indicates to DMP which sensors are available +/* 1: gyro samples available + 2: accel samples available + 8: secondary compass samples available */ +#define DATA_RDY_STATUS (8 * 16 + 10) // 16-bit: indicates to DMP which sensors are available + +// batch mode +#define BM_BATCH_CNTR (27 * 16) // 32-bit: Batch counter +#define BM_BATCH_THLD (19 * 16 + 12) // 32-bit: Batch mode threshold +#define BM_BATCH_MASK (21 * 16 + 14) // 16-bit + +// sensor output data rate: all 16-bit +#define ODR_ACCEL (11 * 16 + 14) // ODR_ACCEL Register for accel ODR +#define ODR_GYRO (11 * 16 + 10) // ODR_GYRO Register for gyro ODR +#define ODR_CPASS (11 * 16 + 6) // ODR_CPASS Register for compass ODR +#define ODR_ALS (11 * 16 + 2) // ODR_ALS Register for ALS ODR +#define ODR_QUAT6 (10 * 16 + 12) // ODR_QUAT6 Register for 6-axis quaternion ODR +#define ODR_QUAT9 (10 * 16 + 8) // ODR_QUAT9 Register for 9-axis quaternion ODR +#define ODR_PQUAT6 (10 * 16 + 4) // ODR_PQUAT6 Register for 6-axis pedometer quaternion ODR +#define ODR_GEOMAG (10 * 16 + 0) // ODR_GEOMAG Register for Geomag rv ODR +#define ODR_PRESSURE (11 * 16 + 12) // ODR_PRESSURE Register for pressure ODR +#define ODR_GYRO_CALIBR (11 * 16 + 8) // ODR_GYRO_CALIBR Register for calibrated gyro ODR +#define ODR_CPASS_CALIBR (11 * 16 + 4) // ODR_CPASS_CALIBR Register for calibrated compass ODR + +// sensor output data rate counter: all 16-bit +#define ODR_CNTR_ACCEL (9 * 16 + 14) // ODR_CNTR_ACCEL Register for accel ODR counter +#define ODR_CNTR_GYRO (9 * 16 + 10) // ODR_CNTR_GYRO Register for gyro ODR counter +#define ODR_CNTR_CPASS (9 * 16 + 6) // ODR_CNTR_CPASS Register for compass ODR counter +#define ODR_CNTR_ALS (9 * 16 + 2) // ODR_CNTR_ALS Register for ALS ODR counter +#define ODR_CNTR_QUAT6 (8 * 16 + 12) // ODR_CNTR_QUAT6 Register for 6-axis quaternion ODR counter +#define ODR_CNTR_QUAT9 (8 * 16 + 8) // ODR_CNTR_QUAT9 Register for 9-axis quaternion ODR counter +#define ODR_CNTR_PQUAT6 (8 * 16 + 4) // ODR_CNTR_PQUAT6 Register for 6-axis pedometer quaternion ODR counter +#define ODR_CNTR_GEOMAG (8 * 16 + 0) // ODR_CNTR_GEOMAG Register for Geomag rv ODR counter +#define ODR_CNTR_PRESSURE (9 * 16 + 12) // ODR_CNTR_PRESSURE Register for pressure ODR counter +#define ODR_CNTR_GYRO_CALIBR (9 * 16 + 8) // ODR_CNTR_GYRO_CALIBR Register for calibrated gyro ODR counter +#define ODR_CNTR_CPASS_CALIBR (9 * 16 + 4) // ODR_CNTR_CPASS_CALIBR Register for calibrated compass ODR counter + +// mounting matrix: all 32-bit +#define CPASS_MTX_00 (23 * 16) // Compass mount matrix and scale +#define CPASS_MTX_01 (23 * 16 + 4) // Compass mount matrix and scale +#define CPASS_MTX_02 (23 * 16 + 8) // Compass mount matrix and scale +#define CPASS_MTX_10 (23 * 16 + 12) // Compass mount matrix and scale +#define CPASS_MTX_11 (24 * 16) // Compass mount matrix and scale +#define CPASS_MTX_12 (24 * 16 + 4) // Compass mount matrix and scale +#define CPASS_MTX_20 (24 * 16 + 8) // Compass mount matrix and scale +#define CPASS_MTX_21 (24 * 16 + 12) // Compass mount matrix and scale +#define CPASS_MTX_22 (25 * 16) // Compass mount matrix and scale + +// bias calibration: all 32-bit +// The biases are 32-bits in chip frame in hardware unit scaled by: +// 2^12 (FSR 4g) for accel, 2^15 for gyro, in uT scaled by 2^16 for compass. +#define GYRO_BIAS_X (139 * 16 + 4) +#define GYRO_BIAS_Y (139 * 16 + 8) +#define GYRO_BIAS_Z (139 * 16 + 12) +#define ACCEL_BIAS_X (110 * 16 + 4) +#define ACCEL_BIAS_Y (110 * 16 + 8) +#define ACCEL_BIAS_Z (110 * 16 + 12) +#define CPASS_BIAS_X (126 * 16 + 4) +#define CPASS_BIAS_Y (126 * 16 + 8) +#define CPASS_BIAS_Z (126 * 16 + 12) + +#define GYRO_ACCURACY (138 * 16 + 2) +#define GYRO_BIAS_SET (138 * 16 + 6) +#define GYRO_LAST_TEMPR (134 * 16) +#define GYRO_SLOPE_X (78 * 16 + 4) +#define GYRO_SLOPE_Y (78 * 16 + 8) +#define GYRO_SLOPE_Z (78 * 16 + 12) + +// parameters for accel calibration +#define ACCEL_ACCURACY (97 * 16) +#define ACCEL_CAL_RESET (77 * 16) +#define ACCEL_VARIANCE_THRESH (93 * 16) +#define ACCEL_CAL_RATE (94 * 16 + 4) // 16-bit: 0 (225Hz, 112Hz, 56Hz) +#define ACCEL_PRE_SENSOR_DATA (97 * 16 + 4) +#define ACCEL_COVARIANCE (101 * 16 + 8) +#define ACCEL_ALPHA_VAR (91 * 16) // 32-bit: 1026019965 (225Hz) 977872018 (112Hz) 882002213 (56Hz) +#define ACCEL_A_VAR (92 * 16) // 32-bit: 47721859 (225Hz) 95869806 (112Hz) 191739611 (56Hz) +#define ACCEL_CAL_INIT (94 * 16 + 2) +#define ACCEL_CAL_SCALE_COVQ_IN_RANGE (194 * 16) +#define ACCEL_CAL_SCALE_COVQ_OUT_RANGE (195 * 16) +#define ACCEL_CAL_TEMPERATURE_SENSITIVITY (194 * 16 + 4) +#define ACCEL_CAL_TEMPERATURE_OFFSET_TRIM (194 * 16 + 12) + +#define CPASS_ACCURACY (37 * 16) +#define CPASS_BIAS_SET (34 * 16 + 14) +#define MAR_MODE (37 * 16 + 2) +#define CPASS_COVARIANCE (115 * 16) +#define CPASS_COVARIANCE_CUR (118 * 16 + 8) +#define CPASS_REF_MAG_3D (122 * 16) +#define CPASS_CAL_INIT (114 * 16) +#define CPASS_EST_FIRST_BIAS (113 * 16) +#define MAG_DISTURB_STATE (113 * 16 + 2) +#define CPASS_VAR_COUNT (112 * 16 + 6) +#define CPASS_COUNT_7 (87 * 16 + 2) +#define CPASS_MAX_INNO (124 * 16) +#define CPASS_BIAS_OFFSET (113 * 16 + 4) +#define CPASS_CUR_BIAS_OFFSET (114 * 16 + 4) +#define CPASS_PRE_SENSOR_DATA (87 * 16 + 4) + +// Compass Cal params to be adjusted according to sampling rate +#define CPASS_TIME_BUFFER (112 * 16 + 14) +#define CPASS_RADIUS_3D_THRESH_ANOMALY (112 * 16 + 8) + +#define CPASS_STATUS_CHK (25 * 16 + 12) + +// gains +#define ACCEL_FB_GAIN (34 * 16) +#define ACCEL_ONLY_GAIN (16 * 16 + 12) // 32-bit: 15252014 (225Hz) 30504029 (112Hz) 61117001 (56Hz) +#define GYRO_SF (19 * 16) // 32-bit: gyro scaling factor + +// 9-axis +#define MAGN_THR_9X (80 * 16) +#define MAGN_LPF_THR_9X (80 * 16 + 8) +#define QFB_THR_9X (80 * 16 + 12) + +// DMP running counter +#define DMPRATE_CNTR (18 * 16 + 4) + +// pedometer +#define PEDSTD_BP_B (49 * 16 + 12) +#define PEDSTD_BP_A4 (52 * 16) +#define PEDSTD_BP_A3 (52 * 16 + 4) +#define PEDSTD_BP_A2 (52 * 16 + 8) +#define PEDSTD_BP_A1 (52 * 16 + 12) +#define PEDSTD_SB (50 * 16 + 8) +#define PEDSTD_SB_TIME (50 * 16 + 12) +#define PEDSTD_PEAKTHRSH (57 * 16 + 8) +#define PEDSTD_TIML (50 * 16 + 10) +#define PEDSTD_TIMH (50 * 16 + 14) +#define PEDSTD_PEAK (57 * 16 + 4) +#define PEDSTD_STEPCTR (54 * 16) +#define PEDSTD_STEPCTR2 (58 * 16 + 8) +#define PEDSTD_TIMECTR (60 * 16 + 4) +#define PEDSTD_DECI (58 * 16) +#define PEDSTD_SB2 (60 * 16 + 14) +#define STPDET_TIMESTAMP (18 * 16 + 8) +#define PEDSTEP_IND (19 * 16 + 4) +#define PED_Y_RATIO (17 * 16 + 0) + +// SMD +#define SMD_VAR_TH (141 * 16 + 12) +#define SMD_VAR_TH_DRIVE (143 * 16 + 12) +#define SMD_DRIVE_TIMER_TH (143 * 16 + 8) +#define SMD_TILT_ANGLE_TH (179 * 16 + 12) +#define BAC_SMD_ST_TH (179 * 16 + 8) +#define BAC_ST_ALPHA4 (180 * 16 + 12) +#define BAC_ST_ALPHA4A (176 * 16 + 12) + +// Wake on Motion +#define WOM_ENABLE (64 * 16 + 14) +#define WOM_STATUS (64 * 16 + 6) +#define WOM_THRESHOLD_DMP (64 * 16) // Renamed by PaulZC to avoid duplication with the Bank 2 Reg 0x13 +#define WOM_CNTR_TH (64 * 16 + 12) + +// Activity Recognition +#define BAC_RATE (48 * 16 + 10) +#define BAC_STATE (179 * 16 + 0) +#define BAC_STATE_PREV (179 * 16 + 4) +#define BAC_ACT_ON (182 * 16 + 0) +#define BAC_ACT_OFF (183 * 16 + 0) +#define BAC_STILL_S_F (177 * 16 + 0) +#define BAC_RUN_S_F (177 * 16 + 4) +#define BAC_DRIVE_S_F (178 * 16 + 0) +#define BAC_WALK_S_F (178 * 16 + 4) +#define BAC_SMD_S_F (178 * 16 + 8) +#define BAC_BIKE_S_F (178 * 16 + 12) +#define BAC_E1_SHORT (146 * 16 + 0) +#define BAC_E2_SHORT (146 * 16 + 4) +#define BAC_E3_SHORT (146 * 16 + 8) +#define BAC_VAR_RUN (148 * 16 + 12) +#define BAC_TILT_INIT (181 * 16 + 0) +#define BAC_MAG_ON (225 * 16 + 0) +#define BAC_PS_ON (74 * 16 + 0) +#define BAC_BIKE_PREFERENCE (173 * 16 + 8) +#define BAC_MAG_I2C_ADDR (229 * 16 + 8) +#define BAC_PS_I2C_ADDR (75 * 16 + 4) +#define BAC_DRIVE_CONFIDENCE (144 * 16 + 0) +#define BAC_WALK_CONFIDENCE (144 * 16 + 4) +#define BAC_SMD_CONFIDENCE (144 * 16 + 8) +#define BAC_BIKE_CONFIDENCE (144 * 16 + 12) +#define BAC_STILL_CONFIDENCE (145 * 16 + 0) +#define BAC_RUN_CONFIDENCE (145 * 16 + 4) +#define BAC_MODE_CNTR (150 * 16) +#define BAC_STATE_T_PREV (185 * 16 + 4) +#define BAC_ACT_T_ON (184 * 16 + 0) +#define BAC_ACT_T_OFF (184 * 16 + 4) +#define BAC_STATE_WRDBS_PREV (185 * 16 + 8) +#define BAC_ACT_WRDBS_ON (184 * 16 + 8) +#define BAC_ACT_WRDBS_OFF (184 * 16 + 12) +#define BAC_ACT_ON_OFF (190 * 16 + 2) +#define PREV_BAC_ACT_ON_OFF (188 * 16 + 2) +#define BAC_CNTR (48 * 16 + 2) + +// Flip/Pick-up +#define FP_VAR_ALPHA (245 * 16 + 8) +#define FP_STILL_TH (246 * 16 + 4) +#define FP_MID_STILL_TH (244 * 16 + 8) +#define FP_NOT_STILL_TH (246 * 16 + 8) +#define FP_VIB_REJ_TH (241 * 16 + 8) +#define FP_MAX_PICKUP_T_TH (244 * 16 + 12) +#define FP_PICKUP_TIMEOUT_TH (248 * 16 + 8) +#define FP_STILL_CONST_TH (246 * 16 + 12) +#define FP_MOTION_CONST_TH (240 * 16 + 8) +#define FP_VIB_COUNT_TH (242 * 16 + 8) +#define FP_STEADY_TILT_TH (247 * 16 + 8) +#define FP_STEADY_TILT_UP_TH (242 * 16 + 12) +#define FP_Z_FLAT_TH_MINUS (243 * 16 + 8) +#define FP_Z_FLAT_TH_PLUS (243 * 16 + 12) +#define FP_DEV_IN_POCKET_TH (76 * 16 + 12) +#define FP_PICKUP_CNTR (247 * 16 + 4) +#define FP_RATE (240 * 16 + 12) + +// Gyro FSR +#define GYRO_FULLSCALE (72 * 16 + 12) + +// Accel FSR +// The DMP scales accel raw data internally to align 1g as 2^25. +// To do this and output hardware unit again as configured FSR, write 0x4000000 to ACC_SCALE DMP register, and write 0x40000 to ACC_SCALE2 DMP register. +#define ACC_SCALE (30 * 16 + 0) // 32-bit: Write accel scaling value for internal use +#define ACC_SCALE2 (79 * 16 + 4) // 32-bit: Write accel scaling down value + +// EIS authentication +#define EIS_AUTH_INPUT (160 * 16 + 4) +#define EIS_AUTH_OUTPUT (160 * 16 + 0) + +// B2S +#define B2S_RATE (48 * 16 + 8) + +// B2S mounting matrix +#define B2S_MTX_00 (208 * 16) +#define B2S_MTX_01 (208 * 16 + 4) +#define B2S_MTX_02 (208 * 16 + 8) +#define B2S_MTX_10 (208 * 16 + 12) +#define B2S_MTX_11 (209 * 16) +#define B2S_MTX_12 (209 * 16 + 4) +#define B2S_MTX_20 (209 * 16 + 8) +#define B2S_MTX_21 (209 * 16 + 12) +#define B2S_MTX_22 (210 * 16) + +// Dmp3 orientation parameters (Q30) initialization +#define Q0_QUAT6 (33 * 16 + 0) +#define Q1_QUAT6 (33 * 16 + 4) +#define Q2_QUAT6 (33 * 16 + 8) +#define Q3_QUAT6 (33 * 16 + 12) + + enum DMP_ODR_Registers + { + DMP_ODR_Reg_Accel = ODR_ACCEL, // ODR_ACCEL Register for accel ODR + DMP_ODR_Reg_Gyro = ODR_GYRO, // ODR_GYRO Register for gyro ODR + DMP_ODR_Reg_Cpass = ODR_CPASS, // ODR_CPASS Register for compass ODR + DMP_ODR_Reg_ALS = ODR_ALS, // ODR_ALS Register for ALS ODR + DMP_ODR_Reg_Quat6 = ODR_QUAT6, // ODR_QUAT6 Register for 6-axis quaternion ODR + DMP_ODR_Reg_Quat9 = ODR_QUAT9, // ODR_QUAT9 Register for 9-axis quaternion ODR + DMP_ODR_Reg_PQuat6 = ODR_PQUAT6, // ODR_PQUAT6 Register for 6-axis pedometer quaternion ODR + DMP_ODR_Reg_Geomag = ODR_GEOMAG, // ODR_GEOMAG Register for Geomag RV ODR + DMP_ODR_Reg_Pressure = ODR_PRESSURE, // ODR_PRESSURE Register for pressure ODR + DMP_ODR_Reg_Gyro_Calibr = ODR_GYRO_CALIBR, // ODR_GYRO_CALIBR Register for calibrated gyro ODR + DMP_ODR_Reg_Cpass_Calibr = ODR_CPASS_CALIBR // ODR_CPASS_CALIBR Register for calibrated compass ODR + }; + + /** @brief Sensor identifier for control function + */ + enum inv_icm20948_sensor + { + INV_ICM20948_SENSOR_ACCELEROMETER = 0, + INV_ICM20948_SENSOR_GYROSCOPE, + INV_ICM20948_SENSOR_RAW_ACCELEROMETER, + INV_ICM20948_SENSOR_RAW_GYROSCOPE, + INV_ICM20948_SENSOR_MAGNETIC_FIELD_UNCALIBRATED, + INV_ICM20948_SENSOR_GYROSCOPE_UNCALIBRATED, + INV_ICM20948_SENSOR_ACTIVITY_CLASSIFICATON, + INV_ICM20948_SENSOR_STEP_DETECTOR, + INV_ICM20948_SENSOR_STEP_COUNTER, + INV_ICM20948_SENSOR_GAME_ROTATION_VECTOR, + INV_ICM20948_SENSOR_ROTATION_VECTOR, + INV_ICM20948_SENSOR_GEOMAGNETIC_ROTATION_VECTOR, + INV_ICM20948_SENSOR_GEOMAGNETIC_FIELD, + INV_ICM20948_SENSOR_WAKEUP_SIGNIFICANT_MOTION, + INV_ICM20948_SENSOR_FLIP_PICKUP, + INV_ICM20948_SENSOR_WAKEUP_TILT_DETECTOR, + INV_ICM20948_SENSOR_GRAVITY, + INV_ICM20948_SENSOR_LINEAR_ACCELERATION, + INV_ICM20948_SENSOR_ORIENTATION, + INV_ICM20948_SENSOR_B2S, + INV_ICM20948_SENSOR_RAW_MAGNETOMETER, + INV_ICM20948_SENSOR_MAX, + }; + + /* enum for android sensor*/ + enum ANDROID_SENSORS + { + ANDROID_SENSOR_META_DATA = 0, // 0 + ANDROID_SENSOR_ACCELEROMETER, // 1 + ANDROID_SENSOR_GEOMAGNETIC_FIELD, // 2 + ANDROID_SENSOR_ORIENTATION, // 3 + ANDROID_SENSOR_GYROSCOPE, // 4 + ANDROID_SENSOR_LIGHT, // 5 + ANDROID_SENSOR_PRESSURE, // 6 + ANDROID_SENSOR_TEMPERATURE, // 7 + ANDROID_SENSOR_WAKEUP_PROXIMITY, // 8 + ANDROID_SENSOR_GRAVITY, // 9 + ANDROID_SENSOR_LINEAR_ACCELERATION, // 10 + ANDROID_SENSOR_ROTATION_VECTOR, // 11 + ANDROID_SENSOR_HUMIDITY, // 12 + ANDROID_SENSOR_AMBIENT_TEMPERATURE, // 13 + ANDROID_SENSOR_MAGNETIC_FIELD_UNCALIBRATED, // 14 + ANDROID_SENSOR_GAME_ROTATION_VECTOR, // 15 + ANDROID_SENSOR_GYROSCOPE_UNCALIBRATED, // 16 + ANDROID_SENSOR_WAKEUP_SIGNIFICANT_MOTION, // 17 + ANDROID_SENSOR_STEP_DETECTOR, // 18 + ANDROID_SENSOR_STEP_COUNTER, // 19 + ANDROID_SENSOR_GEOMAGNETIC_ROTATION_VECTOR, // 20 + ANDROID_SENSOR_HEART_RATE, // 21 + ANDROID_SENSOR_PROXIMITY, // 22 + + ANDROID_SENSOR_WAKEUP_ACCELEROMETER, // 23 + ANDROID_SENSOR_WAKEUP_MAGNETIC_FIELD, // 24 + ANDROID_SENSOR_WAKEUP_ORIENTATION, // 25 + ANDROID_SENSOR_WAKEUP_GYROSCOPE, // 26 + ANDROID_SENSOR_WAKEUP_LIGHT, // 27 + ANDROID_SENSOR_WAKEUP_PRESSURE, // 28 + ANDROID_SENSOR_WAKEUP_GRAVITY, // 29 + ANDROID_SENSOR_WAKEUP_LINEAR_ACCELERATION, // 30 + ANDROID_SENSOR_WAKEUP_ROTATION_VECTOR, // 31 + ANDROID_SENSOR_WAKEUP_RELATIVE_HUMIDITY, // 32 + ANDROID_SENSOR_WAKEUP_AMBIENT_TEMPERATURE, // 33 + ANDROID_SENSOR_WAKEUP_MAGNETIC_FIELD_UNCALIBRATED, // 34 + ANDROID_SENSOR_WAKEUP_GAME_ROTATION_VECTOR, // 35 + ANDROID_SENSOR_WAKEUP_GYROSCOPE_UNCALIBRATED, // 36 + ANDROID_SENSOR_WAKEUP_STEP_DETECTOR, // 37 + ANDROID_SENSOR_WAKEUP_STEP_COUNTER, // 38 + ANDROID_SENSOR_WAKEUP_GEOMAGNETIC_ROTATION_VECTOR, // 39 + ANDROID_SENSOR_WAKEUP_HEART_RATE, // 40 + ANDROID_SENSOR_WAKEUP_TILT_DETECTOR, // 41 + ANDROID_SENSOR_RAW_ACCELEROMETER, // 42 + ANDROID_SENSOR_RAW_GYROSCOPE, // 43 + ANDROID_SENSOR_NUM_MAX, // 44 + + ANDROID_SENSOR_B2S, // 45 + ANDROID_SENSOR_FLIP_PICKUP, // 46 + ANDROID_SENSOR_ACTIVITY_CLASSIFICATON, // 47 + ANDROID_SENSOR_SCREEN_ROTATION, // 48 + SELF_TEST, // 49 + SETUP, // 50 + GENERAL_SENSORS_MAX // 51 + }; + +// Determines which base sensor needs to be on based upon ANDROID_SENSORS 0-31 +#define INV_NEEDS_ACCEL_MASK ((1L << 1) | (1L << 3) | (1L << 9) | (1L << 10) | (1L << 11) | (1L << 15) | (1L << 17) | (1L << 18) | (1L << 19) | (1L << 20) | (1L << 23) | (1L << 25) | (1L << 29) | (1L << 30) | (1L << 31)) +#define INV_NEEDS_GYRO_MASK ((1L << 3) | (1L << 4) | (1L << 9) | (1L << 10) | (1L << 11) | (1L << 15) | (1L << 16) | (1L << 25) | (1L << 26) | (1L << 29) | (1L << 30) | (1L << 31)) +#define INV_NEEDS_COMPASS_MASK ((1L << 2) | (1L << 3) | (1L << 11) | (1L << 14) | (1L << 20) | (1L << 24) | (1L << 25) | (1L << 31)) +#define INV_NEEDS_PRESSURE ((1L << 6) | (1L << 28)) + +// Determines which base sensor needs to be on based upon ANDROID_SENSORS 32- +#define INV_NEEDS_ACCEL_MASK1 ((1L << 3) | (1L << 5) | (1L << 6) | (1L << 7) | (1L << 9) | (1L << 10)) // I.e. 35, 37, 38, 39, 41, 42 +#define INV_NEEDS_GYRO_MASK1 ((1L << 3) | (1L << 4) | (1L << 11)) // I.e. 35, 36, 43 +#define INV_NEEDS_COMPASS_MASK1 ((1L << 2) | (1L << 7)) // I.e. 34 and 39 + + enum DMP_Data_Ready_Status_Register_Bits + { + DMP_Data_ready_Gyro = 0x0001, // Gyro samples available + DMP_Data_ready_Accel = 0x0002, // Accel samples available + DMP_Data_ready_Secondary_Compass = 0x0008 // Secondary compass samples available + }; + + enum DMP_Data_Output_Control_1_Register_Bits + { + DMP_Data_Output_Control_1_Step_Ind_0 = 0x0001, // Pedometer Step Indicator Bit 0 + DMP_Data_Output_Control_1_Step_Ind_1 = 0x0002, // Pedometer Step Indicator Bit 1 + DMP_Data_Output_Control_1_Step_Ind_2 = 0x0004, // Pedometer Step Indicator Bit 2 + DMP_Data_Output_Control_1_Header2 = 0x0008, // Header 2 + DMP_Data_Output_Control_1_Step_Detector = 0x0010, // Pedometer Step Detector + DMP_Data_Output_Control_1_Compass_Calibr = 0x0020, // 32-bit calibrated compass + DMP_Data_Output_Control_1_Gyro_Calibr = 0x0040, // 32-bit calibrated gyro + DMP_Data_Output_Control_1_Pressure = 0x0080, // 16-bit Pressure + DMP_Data_Output_Control_1_Geomag = 0x0100, // 32-bit Geomag rv + heading accuracy + DMP_Data_Output_Control_1_PQuat6 = 0x0200, // 16-bit pedometer quaternion + DMP_Data_Output_Control_1_Quat9 = 0x0400, // 32-bit 9-axis quaternion + heading accuracy + DMP_Data_Output_Control_1_Quat6 = 0x0800, // 32-bit 6-axis quaternion + DMP_Data_Output_Control_1_ALS = 0x1000, // 16-bit ALS + DMP_Data_Output_Control_1_Compass = 0x2000, // 16-bit compass + DMP_Data_Output_Control_1_Gyro = 0x4000, // 16-bit gyro + DMP_Data_Output_Control_1_Accel = 0x8000 // 16-bit accel + }; + + enum DMP_Data_Output_Control_2_Register_Bits + { + DMP_Data_Output_Control_2_Secondary_On_Off = 0x0040, + DMP_Data_Output_Control_2_Activity_Recognition_BAC = 0x0080, + DMP_Data_Output_Control_2_Batch_Mode_Enable = 0x0100, + DMP_Data_Output_Control_2_Pickup = 0x0400, + DMP_Data_Output_Control_2_Fsync_Detection = 0x0800, + DMP_Data_Output_Control_2_Compass_Accuracy = 0x1000, + DMP_Data_Output_Control_2_Gyro_Accuracy = 0x2000, + DMP_Data_Output_Control_2_Accel_Accuracy = 0x4000 + }; + + enum DMP_Motion_Event_Control_Register_Bits + { + DMP_Motion_Event_Control_Activity_Recog_Pedom_Accel = 0x0002, // Activity Recognition / Pedometer accel only + DMP_Motion_Event_Control_Bring_Look_To_See = 0x0004, + DMP_Motion_Event_Control_Geomag = 0x0008, // Geomag rv + DMP_Motion_Event_Control_Pickup = 0x0010, + DMP_Motion_Event_Control_BTS = 0x0020, + DMP_Motion_Event_Control_9axis = 0x0040, + DMP_Motion_Event_Control_Compass_Calibr = 0x0080, + DMP_Motion_Event_Control_Gyro_Calibr = 0x0100, + DMP_Motion_Event_Control_Accel_Calibr = 0x0200, + DMP_Motion_Event_Control_Significant_Motion_Det = 0x0800, + DMP_Motion_Event_Control_Tilt_Interrupt = 0x1000, + DMP_Motion_Event_Control_Pedometer_Interrupt = 0x2000, + DMP_Motion_Event_Control_Activity_Recog_Pedom = 0x4000, + DMP_Motion_Event_Control_BAC_Wearable = 0x8000 + }; + + enum DMP_Header_Bitmap + { + DMP_header_bitmap_Header2 = 0x0008, + DMP_header_bitmap_Step_Detector = 0x0010, + DMP_header_bitmap_Compass_Calibr = 0x0020, + DMP_header_bitmap_Gyro_Calibr = 0x0040, + DMP_header_bitmap_Pressure = 0x0080, + DMP_header_bitmap_Geomag = 0x0100, + DMP_header_bitmap_PQuat6 = 0x0200, + DMP_header_bitmap_Quat9 = 0x0400, + DMP_header_bitmap_Quat6 = 0x0800, + DMP_header_bitmap_ALS = 0x1000, + DMP_header_bitmap_Compass = 0x2000, + DMP_header_bitmap_Gyro = 0x4000, + DMP_header_bitmap_Accel = 0x8000 + }; + + enum DMP_Header2_Bitmap + { + DMP_header2_bitmap_Secondary_On_Off = 0x0040, + DMP_header2_bitmap_Activity_Recog = 0x0080, + DMP_header2_bitmap_Pickup = 0x0400, + DMP_header2_bitmap_Fsync = 0x0800, + DMP_header2_bitmap_Compass_Accuracy = 0x1000, + DMP_header2_bitmap_Gyro_Accuracy = 0x2000, + DMP_header2_bitmap_Accel_Accuracy = 0x4000 + }; + + typedef struct // DMP Activity Recognition data + { + uint8_t Drive : 1; + uint8_t Walk : 1; + uint8_t Run : 1; + uint8_t Bike : 1; + uint8_t Tilt : 1; + uint8_t Still : 1; + uint8_t reserved : 2; + } icm_20948_DMP_Activity_t; + + typedef struct // DMP Secondary On/Off data + { + uint16_t Gyro_Off : 1; + uint16_t Gyro_On : 1; + uint16_t Compass_Off : 1; + uint16_t Compass_On : 1; + uint16_t Proximity_Off : 1; + uint16_t Proximity_On : 1; + uint16_t reserved : 10; + } icm_20948_DMP_Secondary_On_Off_t; + +#define icm_20948_DMP_Header_Bytes 2 +#define icm_20948_DMP_Header2_Bytes 2 +#define icm_20948_DMP_Raw_Accel_Bytes 6 +#define icm_20948_DMP_Raw_Gyro_Bytes 6 +#define icm_20948_DMP_Gyro_Bias_Bytes 6 +#define icm_20948_DMP_Compass_Bytes 6 +#define icm_20948_DMP_ALS_Bytes 8 +#define icm_20948_DMP_Quat6_Bytes 12 +#define icm_20948_DMP_Quat9_Bytes 14 +// <-- lcm20948MPUFifoControl.c suggests icm_20948_DMP_Step_Detector_Bytes comes here <-- +#define icm_20948_DMP_PQuat6_Bytes 6 +#define icm_20948_DMP_Geomag_Bytes 14 +#define icm_20948_DMP_Pressure_Bytes 6 +#define icm_20948_DMP_Gyro_Calibr_Bytes 12 // lcm20948MPUFifoControl.c suggests icm_20948_DMP_Gyro_Calibr_Bytes is not supported? +#define icm_20948_DMP_Compass_Calibr_Bytes 12 +#define icm_20948_DMP_Step_Detector_Bytes 4 // See note above +#define icm_20948_DMP_Accel_Accuracy_Bytes 2 +#define icm_20948_DMP_Gyro_Accuracy_Bytes 2 +#define icm_20948_DMP_Compass_Accuracy_Bytes 2 +#define icm_20948_DMP_Fsync_Detection_Bytes 2 // lcm20948MPUFifoControl.c suggests icm_20948_DMP_Fsync_Detection_Bytes is not supported? +#define icm_20948_DMP_Pickup_Bytes 2 +#define icm_20948_DMP_Activity_Recognition_Bytes 6 +#define icm_20948_DMP_Secondary_On_Off_Bytes 2 +#define icm_20948_DMP_Footer_Bytes 2 +#define icm_20948_DMP_Maximum_Bytes 14 // The most bytes we will attempt to read from the FIFO in one go + + typedef struct + { + uint16_t header; + uint16_t header2; + union + { + uint8_t Bytes[icm_20948_DMP_Raw_Accel_Bytes]; + struct + { + int16_t X; + int16_t Y; + int16_t Z; + } Data; + } Raw_Accel; + union + { + uint8_t Bytes[icm_20948_DMP_Raw_Gyro_Bytes + icm_20948_DMP_Gyro_Bias_Bytes]; + struct + { + int16_t X; + int16_t Y; + int16_t Z; + int16_t BiasX; + int16_t BiasY; + int16_t BiasZ; + } Data; + } Raw_Gyro; + union + { + uint8_t Bytes[icm_20948_DMP_Compass_Bytes]; + struct + { + int16_t X; + int16_t Y; + int16_t Z; + } Data; + } Compass; + uint8_t ALS[icm_20948_DMP_ALS_Bytes]; // Byte[0]: Dummy, Byte[2:1]: Ch0DATA, Byte[4:3]: Ch1DATA, Byte[6:5]: PDATA, Byte[7]: Dummy + // The 6-Axis and 9-axis Quaternion outputs each consist of 12 bytes of data. + // These 12 bytes in turn consists of three 4-byte elements. + // 9-axis quaternion data and Geomag rv is always followed by 2-bytes of heading accuracy, hence the size of Quat9 and Geomag data size in the FIFO is 14 bytes. + // Quaternion data for both cases is cumulative/integrated values. + // For a given quaternion Q, the ordering of its elements is {Q1, Q2, Q3}. + // Each element is represented using Big Endian byte order. + // Q0 value is computed from this equation: Q20 + Q21 + Q22 + Q23 = 1. + // In case of drift, the sum will not add to 1, therefore, quaternion data need to be corrected with right bias values. + // The quaternion data is scaled by 2^30. + union + { + uint8_t Bytes[icm_20948_DMP_Quat6_Bytes]; + struct + { + int32_t Q1; + int32_t Q2; + int32_t Q3; + } Data; + } Quat6; + union + { + uint8_t Bytes[icm_20948_DMP_Quat9_Bytes]; + struct + { + int32_t Q1; + int32_t Q2; + int32_t Q3; + int16_t Accuracy; + } Data; + } Quat9; + union + { + uint8_t Bytes[icm_20948_DMP_PQuat6_Bytes]; + struct + { + int16_t Q1; + int16_t Q2; + int16_t Q3; + } Data; + } PQuat6; + union + { + uint8_t Bytes[icm_20948_DMP_Geomag_Bytes]; + struct + { + int32_t Q1; + int32_t Q2; + int32_t Q3; + int16_t Accuracy; + } Data; + } Geomag; + uint8_t Pressure[6]; // Byte [2:0]: Pressure data, Byte [5:3]: Temperature data + union + { + uint8_t Bytes[icm_20948_DMP_Gyro_Calibr_Bytes]; + struct + { + int32_t X; + int32_t Y; + int32_t Z; + } Data; + } Gyro_Calibr; // Hardware unit scaled by 2^15 + union + { + uint8_t Bytes[icm_20948_DMP_Compass_Calibr_Bytes]; + struct + { + int32_t X; + int32_t Y; + int32_t Z; + } Data; + } Compass_Calibr; // The unit is uT scaled by 2^16 + uint32_t Pedometer_Timestamp; // Timestamp as DMP cycle + uint16_t Accel_Accuracy; // The accuracy is expressed as 0~3. The lowest is 0 and 3 is the highest. + uint16_t Gyro_Accuracy; // The accuracy is expressed as 0~3. The lowest is 0 and 3 is the highest. + uint16_t Compass_Accuracy; // The accuracy is expressed as 0~3. The lowest is 0 and 3 is the highest. + uint16_t Fsync_Delay_Time; // The data is delay time between Fsync event and the 1st ODR event after Fsync event. + uint16_t Pickup; // The value “2” indicates pick up is detected. + // Activity Recognition data + // The data include Start and End states, and timestamp as DMP cycle. + // Byte [0]: State-Start, Byte [1]: State-End, Byte [5:2]: timestamp. + // The states are expressed as below. + // Drive: 0x01 + // Walk: 0x02 + // Run: 0x04 + // Bike: 0x08 + // Tilt: 0x10 + // Still: 0x20 + union + { + uint8_t Bytes[icm_20948_DMP_Activity_Recognition_Bytes]; + struct + { + icm_20948_DMP_Activity_t State_Start; + icm_20948_DMP_Activity_t State_End; + uint32_t Timestamp; + } Data; + } Activity_Recognition; + // Secondary On/Off data + // BAC algorithm requires sensors on/off through FIFO data to detect activities effectively and save power. + // The driver is expected to control sensors accordingly. + // The data indicates which sensor and on or off as below. + // Gyro Off: 0x01 + // Gyro On: 0x02 + // Compass Off: 0x04 + // Compass On: 0x08 + // Proximity Off: 0x10 + // Proximity On: 0x20 + union + { + uint8_t Bytes[icm_20948_DMP_Secondary_On_Off_Bytes]; + icm_20948_DMP_Secondary_On_Off_t Sensors; + } Secondary_On_Off; + uint16_t Footer; // Gyro count? + } icm_20948_DMP_data_t; + +#ifdef __cplusplus +} +#endif /* __cplusplus */ + +#endif /* _ICM_20948_REGISTERS_H_ */ diff --git a/src/util/ICM_20948_ENUMERATIONS.h b/src/util/ICM_20948_ENUMERATIONS.h new file mode 100644 index 0000000..18b2aca --- /dev/null +++ b/src/util/ICM_20948_ENUMERATIONS.h @@ -0,0 +1,263 @@ +/* + +This file contains a useful c translation of the datasheet register map values + +*/ + +#ifndef _ICM_20948_ENUMERATIONS_H_ +#define _ICM_20948_ENUMERATIONS_H_ + +#ifdef __cplusplus +extern "C" +{ +#endif /* __cplusplus */ + + // // Generalized + // REG_BANK_SEL = 0x7F, + + // // Gyroscope and Accelerometer + // // User Bank 0 + // AGB0_REG_WHO_AM_I = 0x00, + // // Break + // AGB0_REG_USER_CTRL = 0x03, + // // Break + // AGB0_REG_LP_CONFIG = 0x05, + + typedef enum + { + ICM_20948_Sample_Mode_Continuous = 0x00, + ICM_20948_Sample_Mode_Cycled, + } ICM_20948_LP_CONFIG_CYCLE_e; + + // AGB0_REG_PWR_MGMT_1, + + typedef enum + { + ICM_20948_Clock_Internal_20MHz = 0x00, + ICM_20948_Clock_Auto, + ICM_20948_Clock_TimingReset = 0x07 + } ICM_20948_PWR_MGMT_1_CLKSEL_e; + + // AGB0_REG_PWR_MGMT_2, + // // Break + // AGB0_REG_INT_PIN_CONFIG = 0x0F, + // AGB0_REG_INT_ENABLE, + // AGB0_REG_INT_ENABLE_1, + // AGB0_REG_INT_ENABLE_2, + // AGB0_REG_INT_ENABLE_3, + // // Break + // AGB0_REG_I2C_MST_STATUS = 0x17, + // // Break + // AGB0_REG_INT_STATUS = 0x19, + // AGB0_REG_INT_STATUS_1, + // AGB0_REG_INT_STATUS_2, + // AGB0_REG_INT_STATUS_3, + // // Break + // AGB0_REG_DELAY_TIMEH = 0x28, + // AGB0_REG_DELAY_TIMEL, + // // Break + // AGB0_REG_ACCEL_XOUT_H = 0x2D, + // AGB0_REG_ACCEL_XOUT_L, + // AGB0_REG_ACCEL_YOUT_H, + // AGB0_REG_ACCEL_YOUT_L, + // AGB0_REG_ACCEL_ZOUT_H, + // AGB0_REG_ACCEL_ZOUT_L, + // AGB0_REG_GYRO_XOUT_H, + // AGB0_REG_GYRO_XOUT_L, + // AGB0_REG_GYRO_YOUT_H, + // AGB0_REG_GYRO_YOUT_L, + // AGB0_REG_GYRO_ZOUT_H, + // AGB0_REG_GYRO_ZOUT_L, + // AGB0_REG_TEMP_OUT_H, + // AGB0_REG_TEMP_OUT_L, + // AGB0_REG_EXT_PERIPH_SENS_DATA_00, + // AGB0_REG_EXT_PERIPH_SENS_DATA_01, + // AGB0_REG_EXT_PERIPH_SENS_DATA_02, + // AGB0_REG_EXT_PERIPH_SENS_DATA_03, + // AGB0_REG_EXT_PERIPH_SENS_DATA_04, + // AGB0_REG_EXT_PERIPH_SENS_DATA_05, + // AGB0_REG_EXT_PERIPH_SENS_DATA_06, + // AGB0_REG_EXT_PERIPH_SENS_DATA_07, + // AGB0_REG_EXT_PERIPH_SENS_DATA_08, + // AGB0_REG_EXT_PERIPH_SENS_DATA_09, + // AGB0_REG_EXT_PERIPH_SENS_DATA_10, + // AGB0_REG_EXT_PERIPH_SENS_DATA_11, + // AGB0_REG_EXT_PERIPH_SENS_DATA_12, + // AGB0_REG_EXT_PERIPH_SENS_DATA_13, + // AGB0_REG_EXT_PERIPH_SENS_DATA_14, + // AGB0_REG_EXT_PERIPH_SENS_DATA_15, + // AGB0_REG_EXT_PERIPH_SENS_DATA_16, + // AGB0_REG_EXT_PERIPH_SENS_DATA_17, + // AGB0_REG_EXT_PERIPH_SENS_DATA_18, + // AGB0_REG_EXT_PERIPH_SENS_DATA_19, + // AGB0_REG_EXT_PERIPH_SENS_DATA_20, + // AGB0_REG_EXT_PERIPH_SENS_DATA_21, + // AGB0_REG_EXT_PERIPH_SENS_DATA_22, + // AGB0_REG_EXT_PERIPH_SENS_DATA_23, + // // Break + // AGB0_REG_FIFO_EN_1 = 0x66, + // AGB0_REG_FIFO_EN_2, + // AGB0_REG_FIFO_MODE, + // // Break + // AGB0_REG_FIFO_COUNT_H = 0x70, + // AGB0_REG_FIFO_COUNT_L, + // AGB0_REG_FIFO_R_W, + // // Break + // AGB0_REG_DATA_RDY_STATUS = 0x74, + // // Break + // AGB0_REG_FIFO_CFG = 0x76, + // // Break + // AGB0_REG_MEM_START_ADDR = 0x7C, // Hmm, Invensense thought they were sneaky not listing these locations on the datasheet... + // AGB0_REG_MEM_R_W = 0x7D, // These three locations seem to be able to access some memory within the device + // AGB0_REG_MEM_BANK_SEL = 0x7E, // And that location is also where the DMP image gets loaded + // AGB0_REG_REG_BANK_SEL = 0x7F, + + // // Bank 1 + // AGB1_REG_SELF_TEST_X_GYRO = 0x02, + // AGB1_REG_SELF_TEST_Y_GYRO, + // AGB1_REG_SELF_TEST_Z_GYRO, + // // Break + // AGB1_REG_SELF_TEST_X_ACCEL = 0x0E, + // AGB1_REG_SELF_TEST_Y_ACCEL, + // AGB1_REG_SELF_TEST_Z_ACCEL, + // // Break + // AGB1_REG_XA_OFFS_H = 0x14, + // AGB1_REG_XA_OFFS_L, + // // Break + // AGB1_REG_YA_OFFS_H = 0x17, + // AGB1_REG_YA_OFFS_L, + // // Break + // AGB1_REG_ZA_OFFS_H = 0x1A, + // AGB1_REG_ZA_OFFS_L, + // // Break + // AGB1_REG_TIMEBASE_CORRECTION_PLL = 0x28, + // // Break + // AGB1_REG_REG_BANK_SEL = 0x7F, + + // // Bank 2 + // AGB2_REG_GYRO_SMPLRT_DIV = 0x00, + + /* +Gyro sample rate divider. Divides the internal sample rate to generate the sample +rate that controls sensor data output rate, FIFO sample rate, and DMP sequence rate. +NOTE: This register is only effective when FCHOICE = 1’b1 (FCHOICE_B register bit is 1’b0), and +(0 < DLPF_CFG < 7). +ODR is computed as follows: +1.1 kHz/(1+GYRO_SMPLRT_DIV[7:0]) +*/ + + // AGB2_REG_GYRO_CONFIG_1, + + typedef enum + { // Full scale range options in degrees per second + dps250 = 0x00, + dps500, + dps1000, + dps2000, + } ICM_20948_GYRO_CONFIG_1_FS_SEL_e; + + typedef enum + { // Format is dAbwB_nXbwY - A is integer part of 3db BW, B is fraction. X is integer part of nyquist bandwidth, Y is fraction + gyr_d196bw6_n229bw8 = 0x00, + gyr_d151bw8_n187bw6, + gyr_d119bw5_n154bw3, + gyr_d51bw2_n73bw3, + gyr_d23bw9_n35bw9, + gyr_d11bw6_n17bw8, + gyr_d5bw7_n8bw9, + gyr_d361bw4_n376bw5, + } ICM_20948_GYRO_CONFIG_1_DLPCFG_e; + + // AGB2_REG_GYRO_CONFIG_2, + // AGB2_REG_XG_OFFS_USRH, + // AGB2_REG_XG_OFFS_USRL, + // AGB2_REG_YG_OFFS_USRH, + // AGB2_REG_YG_OFFS_USRL, + // AGB2_REG_ZG_OFFS_USRH, + // AGB2_REG_ZG_OFFS_USRL, + // AGB2_REG_ODR_ALIGN_EN, + // // Break + // AGB2_REG_ACCEL_SMPLRT_DIV_1 = 0x10, + // AGB2_REG_ACCEL_SMPLRT_DIV_2, + // AGB2_REG_ACCEL_INTEL_CTRL, + // AGB2_REG_ACCEL_WOM_THR, + // AGB2_REG_ACCEL_CONFIG, + + typedef enum + { + gpm2 = 0x00, + gpm4, + gpm8, + gpm16, + } ICM_20948_ACCEL_CONFIG_FS_SEL_e; + + typedef enum + { // Format is dAbwB_nXbwZ - A is integer part of 3db BW, B is fraction. X is integer part of nyquist bandwidth, Y is fraction + acc_d246bw_n265bw = 0x00, + acc_d246bw_n265bw_1, + acc_d111bw4_n136bw, + acc_d50bw4_n68bw8, + acc_d23bw9_n34bw4, + acc_d11bw5_n17bw, + acc_d5bw7_n8bw3, + acc_d473bw_n499bw, + } ICM_20948_ACCEL_CONFIG_DLPCFG_e; + + // AGB2_REG_ACCEL_CONFIG_2, + // // Break + // AGB2_REG_FSYNC_CONFIG = 0x52, + // AGB2_REG_TEMP_CONFIG, + // AGB2_REG_MOD_CTRL_USR, + // // Break + // AGB2_REG_REG_BANK_SEL = 0x7F, + + // // Bank 3 + // AGB3_REG_I2C_MST_ODR_CONFIG = 0x00, + // AGB3_REG_I2C_MST_CTRL, + // AGB3_REG_I2C_MST_DELAY_CTRL, + // AGB3_REG_I2C_PERIPH0_ADDR, + // AGB3_REG_I2C_PERIPH0_REG, + // AGB3_REG_I2C_PERIPH0_CTRL, + // AGB3_REG_I2C_PERIPH0_DO, + // AGB3_REG_I2C_PERIPH1_ADDR, + // AGB3_REG_I2C_PERIPH1_REG, + // AGB3_REG_I2C_PERIPH1_CTRL, + // AGB3_REG_I2C_PERIPH1_DO, + // AGB3_REG_I2C_PERIPH2_ADDR, + // AGB3_REG_I2C_PERIPH2_REG, + // AGB3_REG_I2C_PERIPH2_CTRL, + // AGB3_REG_I2C_PERIPH2_DO, + // AGB3_REG_I2C_PERIPH3_ADDR, + // AGB3_REG_I2C_PERIPH3_REG, + // AGB3_REG_I2C_PERIPH3_CTRL, + // AGB3_REG_I2C_PERIPH3_DO, + // AGB3_REG_I2C_PERIPH4_ADDR, + // AGB3_REG_I2C_PERIPH4_REG, + // AGB3_REG_I2C_PERIPH4_CTRL, + // AGB3_REG_I2C_PERIPH4_DO, + // AGB3_REG_I2C_PERIPH4_DI, + // // Break + // AGB3_REG_REG_BANK_SEL = 0x7F, + + // // Magnetometer + // M_REG_WIA2 = 0x01, + // // Break + // M_REG_ST1 = 0x10, + // M_REG_HXL, + // M_REG_HXH, + // M_REG_HYL, + // M_REG_HYH, + // M_REG_HZL, + // M_REG_HZH, + // M_REG_ST2, + // // Break + // M_REG_CNTL2 = 0x31, + // M_REG_CNTL3, + // M_REG_TS1, + // M_REG_TS2, + +#ifdef __cplusplus +} +#endif /* __cplusplus */ + +#endif /* _ICM_20948_ENUMERATIONS_H_ */ diff --git a/src/util/ICM_20948_REGISTERS.h b/src/util/ICM_20948_REGISTERS.h new file mode 100644 index 0000000..fb0e21f --- /dev/null +++ b/src/util/ICM_20948_REGISTERS.h @@ -0,0 +1,810 @@ +/* + +This file contains a useful c translation of the datasheet register map + +*/ + +#ifndef _ICM_20948_REGISTERS_H_ +#define _ICM_20948_REGISTERS_H_ + +#include + +#ifdef __cplusplus +extern "C" +{ +#endif /* __cplusplus */ + + typedef enum + { + // Generalized + REG_BANK_SEL = 0x7F, + + // Gyroscope and Accelerometer + // User Bank 0 + AGB0_REG_WHO_AM_I = 0x00, + AGB0_REG_LPF, + // Break + AGB0_REG_USER_CTRL = 0x03, + // Break + AGB0_REG_LP_CONFIG = 0x05, + AGB0_REG_PWR_MGMT_1, + AGB0_REG_PWR_MGMT_2, + // Break + AGB0_REG_INT_PIN_CONFIG = 0x0F, + AGB0_REG_INT_ENABLE, + AGB0_REG_INT_ENABLE_1, + AGB0_REG_INT_ENABLE_2, + AGB0_REG_INT_ENABLE_3, + // Break + AGB0_REG_I2C_MST_STATUS = 0x17, + AGB0_REG_DMP_INT_STATUS, + AGB0_REG_INT_STATUS, + AGB0_REG_INT_STATUS_1, + AGB0_REG_INT_STATUS_2, + AGB0_REG_INT_STATUS_3, + // Break + AGB0_REG_SINGLE_FIFO_PRIORITY_SEL = 0x26, + // Break + AGB0_REG_DELAY_TIMEH = 0x28, + AGB0_REG_DELAY_TIMEL, + // Break + AGB0_REG_ACCEL_XOUT_H = 0x2D, + AGB0_REG_ACCEL_XOUT_L, + AGB0_REG_ACCEL_YOUT_H, + AGB0_REG_ACCEL_YOUT_L, + AGB0_REG_ACCEL_ZOUT_H, + AGB0_REG_ACCEL_ZOUT_L, + AGB0_REG_GYRO_XOUT_H, + AGB0_REG_GYRO_XOUT_L, + AGB0_REG_GYRO_YOUT_H, + AGB0_REG_GYRO_YOUT_L, + AGB0_REG_GYRO_ZOUT_H, + AGB0_REG_GYRO_ZOUT_L, + AGB0_REG_TEMP_OUT_H, + AGB0_REG_TEMP_OUT_L, + AGB0_REG_EXT_PERIPH_SENS_DATA_00, + AGB0_REG_EXT_PERIPH_SENS_DATA_01, + AGB0_REG_EXT_PERIPH_SENS_DATA_02, + AGB0_REG_EXT_PERIPH_SENS_DATA_03, + AGB0_REG_EXT_PERIPH_SENS_DATA_04, + AGB0_REG_EXT_PERIPH_SENS_DATA_05, + AGB0_REG_EXT_PERIPH_SENS_DATA_06, + AGB0_REG_EXT_PERIPH_SENS_DATA_07, + AGB0_REG_EXT_PERIPH_SENS_DATA_08, + AGB0_REG_EXT_PERIPH_SENS_DATA_09, + AGB0_REG_EXT_PERIPH_SENS_DATA_10, + AGB0_REG_EXT_PERIPH_SENS_DATA_11, + AGB0_REG_EXT_PERIPH_SENS_DATA_12, + AGB0_REG_EXT_PERIPH_SENS_DATA_13, + AGB0_REG_EXT_PERIPH_SENS_DATA_14, + AGB0_REG_EXT_PERIPH_SENS_DATA_15, + AGB0_REG_EXT_PERIPH_SENS_DATA_16, + AGB0_REG_EXT_PERIPH_SENS_DATA_17, + AGB0_REG_EXT_PERIPH_SENS_DATA_18, + AGB0_REG_EXT_PERIPH_SENS_DATA_19, + AGB0_REG_EXT_PERIPH_SENS_DATA_20, + AGB0_REG_EXT_PERIPH_SENS_DATA_21, + AGB0_REG_EXT_PERIPH_SENS_DATA_22, + AGB0_REG_EXT_PERIPH_SENS_DATA_23, + // Break + AGB0_REG_TEMP_CONFIG = 0x53, + // Break + AGB0_REG_FIFO_EN_1 = 0x66, + AGB0_REG_FIFO_EN_2, + AGB0_REG_FIFO_RST, + AGB0_REG_FIFO_MODE, + // Break + AGB0_REG_FIFO_COUNT_H = 0x70, + AGB0_REG_FIFO_COUNT_L, + AGB0_REG_FIFO_R_W, + // Break + AGB0_REG_DATA_RDY_STATUS = 0x74, + AGB0_REG_HW_FIX_DISABLE, + AGB0_REG_FIFO_CFG, + // Break + AGB0_REG_MEM_START_ADDR = 0x7C, // Hmm, Invensense thought they were sneaky not listing these locations on the datasheet... + AGB0_REG_MEM_R_W = 0x7D, // These three locations seem to be able to access some memory within the device + AGB0_REG_MEM_BANK_SEL = 0x7E, // And that location is also where the DMP image gets loaded + AGB0_REG_REG_BANK_SEL = 0x7F, + + // Bank 1 + AGB1_REG_SELF_TEST_X_GYRO = 0x02, + AGB1_REG_SELF_TEST_Y_GYRO, + AGB1_REG_SELF_TEST_Z_GYRO, + // Break + AGB1_REG_SELF_TEST_X_ACCEL = 0x0E, + AGB1_REG_SELF_TEST_Y_ACCEL, + AGB1_REG_SELF_TEST_Z_ACCEL, + // Break + AGB1_REG_XA_OFFS_H = 0x14, + AGB1_REG_XA_OFFS_L, + // Break + AGB1_REG_YA_OFFS_H = 0x17, + AGB1_REG_YA_OFFS_L, + // Break + AGB1_REG_ZA_OFFS_H = 0x1A, + AGB1_REG_ZA_OFFS_L, + // Break + AGB1_REG_TIMEBASE_CORRECTION_PLL = 0x28, + // Break + AGB1_REG_REG_BANK_SEL = 0x7F, + + // Bank 2 + AGB2_REG_GYRO_SMPLRT_DIV = 0x00, + AGB2_REG_GYRO_CONFIG_1, + AGB2_REG_GYRO_CONFIG_2, + AGB2_REG_XG_OFFS_USRH, + AGB2_REG_XG_OFFS_USRL, + AGB2_REG_YG_OFFS_USRH, + AGB2_REG_YG_OFFS_USRL, + AGB2_REG_ZG_OFFS_USRH, + AGB2_REG_ZG_OFFS_USRL, + AGB2_REG_ODR_ALIGN_EN, + // Break + AGB2_REG_ACCEL_SMPLRT_DIV_1 = 0x10, + AGB2_REG_ACCEL_SMPLRT_DIV_2, + AGB2_REG_ACCEL_INTEL_CTRL, + AGB2_REG_ACCEL_WOM_THR, + AGB2_REG_ACCEL_CONFIG, + AGB2_REG_ACCEL_CONFIG_2, + // Break + AGB2_REG_PRS_ODR_CONFIG = 0x20, + // Break + AGB2_REG_PRGM_START_ADDRH = 0x50, + AGB2_REG_PRGM_START_ADDRL, + AGB2_REG_FSYNC_CONFIG, + AGB2_REG_TEMP_CONFIG, + AGB2_REG_MOD_CTRL_USR, + // Break + AGB2_REG_REG_BANK_SEL = 0x7F, + + // Bank 3 + AGB3_REG_I2C_MST_ODR_CONFIG = 0x00, + AGB3_REG_I2C_MST_CTRL, + AGB3_REG_I2C_MST_DELAY_CTRL, + AGB3_REG_I2C_PERIPH0_ADDR, + AGB3_REG_I2C_PERIPH0_REG, + AGB3_REG_I2C_PERIPH0_CTRL, + AGB3_REG_I2C_PERIPH0_DO, + AGB3_REG_I2C_PERIPH1_ADDR, + AGB3_REG_I2C_PERIPH1_REG, + AGB3_REG_I2C_PERIPH1_CTRL, + AGB3_REG_I2C_PERIPH1_DO, + AGB3_REG_I2C_PERIPH2_ADDR, + AGB3_REG_I2C_PERIPH2_REG, + AGB3_REG_I2C_PERIPH2_CTRL, + AGB3_REG_I2C_PERIPH2_DO, + AGB3_REG_I2C_PERIPH3_ADDR, + AGB3_REG_I2C_PERIPH3_REG, + AGB3_REG_I2C_PERIPH3_CTRL, + AGB3_REG_I2C_PERIPH3_DO, + AGB3_REG_I2C_PERIPH4_ADDR, + AGB3_REG_I2C_PERIPH4_REG, + AGB3_REG_I2C_PERIPH4_CTRL, + AGB3_REG_I2C_PERIPH4_DO, + AGB3_REG_I2C_PERIPH4_DI, + // Break + AGB3_REG_REG_BANK_SEL = 0x7F, + + // Magnetometer + M_REG_WIA2 = 0x01, + // Break + M_REG_ST1 = 0x10, + M_REG_HXL, + M_REG_HXH, + M_REG_HYL, + M_REG_HYH, + M_REG_HZL, + M_REG_HZH, + M_REG_ST2, + // Break + M_REG_CNTL2 = 0x31, + M_REG_CNTL3, + M_REG_TS1, + M_REG_TS2, + } ICM_20948_Reg_Addr_e; // These enums are not needed for the user, so they stay in this scope (simplifies naming among other things) + + // Type definitions for the registers + typedef struct + { + uint8_t WHO_AM_I; + } ICM_20948_WHO_AM_I_t; + + typedef struct + { + uint8_t reserved_0 : 1; + uint8_t I2C_MST_RST : 1; + uint8_t SRAM_RST : 1; + uint8_t DMP_RST : 1; + uint8_t I2C_IF_DIS : 1; + uint8_t I2C_MST_EN : 1; + uint8_t FIFO_EN : 1; + uint8_t DMP_EN : 1; + } ICM_20948_USER_CTRL_t; + + typedef struct + { + uint8_t reserved_0 : 4; + uint8_t GYRO_CYCLE : 1; + uint8_t ACCEL_CYCLE : 1; + uint8_t I2C_MST_CYCLE : 1; + uint8_t reserved_1 : 1; + } ICM_20948_LP_CONFIG_t; + + typedef struct + { + uint8_t CLKSEL : 3; + uint8_t TEMP_DIS : 1; + uint8_t reserved_0 : 1; + uint8_t LP_EN : 1; + uint8_t SLEEP : 1; + uint8_t DEVICE_RESET : 1; + } ICM_20948_PWR_MGMT_1_t; + + typedef struct + { + uint8_t DISABLE_GYRO : 3; + uint8_t DIABLE_ACCEL : 3; + uint8_t reserved_0 : 2; + } ICM_20948_PWR_MGMT_2_t; + + typedef struct + { + uint8_t reserved_0 : 1; + uint8_t BYPASS_EN : 1; + uint8_t FSYNC_INT_MODE_EN : 1; + uint8_t ACTL_FSYNC : 1; + uint8_t INT_ANYRD_2CLEAR : 1; + uint8_t INT1_LATCH_EN : 1; + uint8_t INT1_OPEN : 1; + uint8_t INT1_ACTL : 1; + } ICM_20948_INT_PIN_CFG_t; + + typedef struct + { + uint8_t I2C_MST_INT_EN : 1; + uint8_t DMP_INT1_EN : 1; + uint8_t PLL_READY_EN : 1; + uint8_t WOM_INT_EN : 1; + uint8_t reserved_0 : 3; + uint8_t REG_WOF_EN : 1; + } ICM_20948_INT_ENABLE_t; + + typedef struct + { + uint8_t RAW_DATA_0_RDY_EN : 1; + uint8_t reserved_0 : 7; + } ICM_20948_INT_ENABLE_1_t; + + typedef union + { + struct + { + uint8_t FIFO_OVERFLOW_EN_40 : 5; + uint8_t reserved_0 : 3; + } grouped; + struct + { + uint8_t FIFO_OVERFLOW_EN_0 : 1; + uint8_t FIFO_OVERFLOW_EN_1 : 1; + uint8_t FIFO_OVERFLOW_EN_2 : 1; + uint8_t FIFO_OVERFLOW_EN_3 : 1; + uint8_t FIFO_OVERFLOW_EN_4 : 1; + uint8_t reserved_0 : 3; + } individual; + } ICM_20948_INT_ENABLE_2_t; + + // typedef struct{ + // uint8_t FIFO_OVERFLOW_EN_40 : 5; + // uint8_t reserved_0 : 3; + // }ICM_20948_INT_ENABLE_2_t; + + typedef union + { + struct + { + uint8_t FIFO_WM_EN_40 : 5; + uint8_t reserved_0 : 3; + } grouped; + struct + { + uint8_t FIFO_WM_EN_0 : 1; + uint8_t FIFO_WM_EN_1 : 1; + uint8_t FIFO_WM_EN_2 : 1; + uint8_t FIFO_WM_EN_3 : 1; + uint8_t FIFO_WM_EN_4 : 1; + uint8_t reserved_0 : 3; + } individual; + } ICM_20948_INT_ENABLE_3_t; + + // typedef struct{ + // uint8_t FIFO_WM_EN_40 : 5; + // uint8_t reserved_0 : 3; + // }ICM_20948_INT_ENABLE_3_t; + + typedef struct + { + uint8_t I2C_PERIPH0_NACK : 1; + uint8_t I2C_PERIPH1_NACK : 1; + uint8_t I2C_PERIPH2_NACK : 1; + uint8_t I2C_PERIPH3_NACK : 1; + uint8_t I2C_PERIPH4_NACK : 1; + uint8_t I2C_LOST_ARB : 1; + uint8_t I2C_PERIPH4_DONE : 1; + uint8_t PASS_THROUGH : 1; + } ICM_20948_I2C_MST_STATUS_t; + + typedef struct + { + uint8_t reserved0 : 1; + uint8_t DMP_INT_Motion_Detect_SMD : 1; + uint8_t reserved1 : 1; + uint8_t DMP_INT_Tilt_Event : 1; + uint8_t reserved2 : 4; + } ICM_20948_DMP_INT_STATUS_t; // Mostly guesswork from InvenSense App Note + + typedef struct + { + uint8_t I2C_MST_INT : 1; + uint8_t DMP_INT1 : 1; + uint8_t PLL_RDY_INT : 1; + uint8_t WOM_INT : 1; + uint8_t reserved_0 : 4; + } ICM_20948_INT_STATUS_t; + + typedef struct + { + uint8_t RAW_DATA_0_RDY_INT : 1; + uint8_t reserved_0 : 7; + } ICM_20948_INT_STATUS_1_t; + + // typedef union{ + // struct{ + // uint8_t FIFO_OVERFLOW_INT_40 : 5; + // uint8_t reserved_0 : 3; + // }grouped; + // struct{ + // uint8_t FIFO_OVERFLOW_INT_0 : 1; + // uint8_t FIFO_OVERFLOW_INT_1 : 1; + // uint8_t FIFO_OVERFLOW_INT_2 : 1; + // uint8_t FIFO_OVERFLOW_INT_3 : 1; + // uint8_t FIFO_OVERFLOW_INT_4 : 1; + // uint8_t reserved_0 : 3; + // }individual; + // }ICM_20948_INT_STATUS_2_t; + + typedef struct + { + uint8_t FIFO_OVERFLOW_INT_40 : 5; + uint8_t reserved_0 : 3; + } ICM_20948_INT_STATUS_2_t; + + // typedef union{ + // struct{ + // uint8_t FIFO_WM_INT_40 : 5; + // uint8_t reserved_0 : 3; + // }grouped; + // struct{ + // uint8_t FIFO_WM_INT_0 : 1; + // uint8_t FIFO_WM_INT_1 : 1; + // uint8_t FIFO_WM_INT_2 : 1; + // uint8_t FIFO_WM_INT_3 : 1; + // uint8_t FIFO_WM_INT_4 : 1; + // uint8_t reserved_0 : 3; + // }individual; + // }ICM_20948_INT_STATUS_3_t; + + typedef struct + { + uint8_t FIFO_WM_INT40 : 5; + uint8_t reserved_0 : 3; + } ICM_20948_INT_STATUS_3_t; + + typedef struct + { + uint8_t DELAY_TIMEH; + } ICM_20948_DELAY_TIMEH_t; + + typedef struct + { + uint8_t DELAY_TIMEL; + } ICM_20948_DELAY_TIMEL_t; + + typedef struct + { + uint8_t ACCEL_XOUT_H; + } ICM_20948_ACCEL_XOUT_H_t; + + typedef struct + { + uint8_t ACCEL_XOUT_L; + } ICM_20948_ACCEL_XOUT_L_t; + + typedef struct + { + uint8_t ACCEL_YOUT_H; + } ICM_20948_ACCEL_YOUT_H_t; + + typedef struct + { + uint8_t ACCEL_YOUT_L; + } ICM_20948_ACCEL_YOUT_L_t; + + typedef struct + { + uint8_t ACCEL_ZOUT_H; + } ICM_20948_ACCEL_ZOUT_H_t; + + typedef struct + { + uint8_t ACCEL_ZOUT_L; + } ICM_20948_ACCEL_ZOUT_L_t; + + typedef struct + { + uint8_t GYRO_XOUT_H; + } ICM_20948_GYRO_XOUT_H_t; + + typedef struct + { + uint8_t GYRO_XOUT_L; + } ICM_20948_GYRO_XOUT_L_t; + + typedef struct + { + uint8_t GYRO_YOUT_H; + } ICM_20948_GYRO_YOUT_H_t; + + typedef struct + { + uint8_t GYRO_YOUT_L; + } ICM_20948_GYRO_YOUT_L_t; + + typedef struct + { + uint8_t GYRO_ZOUT_H; + } ICM_20948_GYRO_ZOUT_H_t; + + typedef struct + { + uint8_t GYRO_ZOUT_L; + } ICM_20948_GYRO_ZOUT_L_t; + + typedef struct + { + uint8_t TEMP_OUT_H; + } ICM_20948_TEMP_OUT_H_t; + + typedef struct + { + uint8_t TEMP_OUT_L; + } ICM_20948_TEMP_OUT_L_t; + + typedef struct + { + uint8_t DATA; // Note: this is not worth copying 24 times, despite there being 24 registers like this one + } ICM_20948_EXT_PERIPH_SENS_DATA_t; + + typedef struct + { + uint8_t PERIPH_0_FIFO_EN : 1; + uint8_t PERIPH_1_FIFO_EN : 1; + uint8_t PERIPH_2_FIFO_EN : 1; + uint8_t PERIPH_3_FIFO_EN : 1; + uint8_t reserved_0 : 4; + } ICM_20948_FIFO_EN_1_t; + + typedef struct + { + uint8_t TEMP_FIFO_EN : 1; + uint8_t GYRO_X_FIFO_EN : 1; + uint8_t GYRO_Y_FIFO_EN : 1; + uint8_t GYRO_Z_FIFO_EN : 1; + uint8_t ACCEL_FIFO_EN : 1; + uint8_t reserved_0 : 3; + } ICM_20948_FIFO_EN_2_t; + + typedef struct + { + uint8_t FIFO_RESET : 5; + uint8_t reserved_0 : 3; + } ICM_20948_FIFO_RST_t; + + typedef struct + { + uint8_t FIFO_MODE : 5; + uint8_t reserved_0 : 3; + } ICM_20948_FIFO_MODE_t; + + typedef struct + { + uint8_t FIFO_COUNTH; + } ICM_20948_FIFO_COUNTH_t; + + typedef struct + { + uint8_t FIFO_COUNTL; + } ICM_20948_FIFO_COUNTL_t; + + typedef struct + { + uint8_t RAW_DATA_RDY : 4; + uint8_t reserved_0 : 3; + uint8_t WOF_STATUS : 1; + } ICM_20948_DATA_RDY_STATUS_t; + + typedef struct + { + uint8_t FIFO_CFG : 1; + uint8_t reserved_0 : 7; + } ICM_20948_FIFO_CFG_t; + + // User bank 1 Types + + typedef struct + { + uint8_t XG_ST_DATA; + } ICM_20948_SELF_TEST_X_GYRO_t; + + typedef struct + { + uint8_t YG_ST_DATA; + } ICM_20948_SELF_TEST_Y_GYRO_t; + + typedef struct + { + uint8_t ZG_ST_DATA; + } ICM_20948_SELF_TEST_Z_GYRO_t; + + typedef struct + { + uint8_t XA_ST_DATA; + } ICM_20948_SELF_TEST_X_ACCEL_t; + + typedef struct + { + uint8_t YA_ST_DATA; + } ICM_20948_SELF_TEST_Y_ACCEL_t; + + typedef struct + { + uint8_t ZA_ST_DATA; + } ICM_20948_SELF_TEST_Z_ACCEL_t; + + typedef struct + { + uint8_t XA_OFFS_14_7; + } ICM_20948_XA_OFFS_H_t; + + typedef struct + { + uint8_t reserved_0 : 1; + uint8_t XA_OFFS_6_0 : 7; + } ICM_20948_XA_OFFS_L_t; + + typedef struct + { + uint8_t YA_OFFS_14_7; + } ICM_20948_YA_OFFS_H_t; + + typedef struct + { + uint8_t reserved_0 : 1; + uint8_t YA_OFFS_6_0 : 7; + } ICM_20948_YA_OFFS_L_t; + + typedef struct + { + uint8_t ZA_OFFS_14_7; + } ICM_20948_ZA_OFFS_H_t; + + typedef struct + { + uint8_t reserved_0 : 1; + uint8_t ZA_OFFS_6_0 : 7; + } ICM_20948_ZA_OFFS_L_t; + + typedef struct + { + uint8_t TBC_PLL; + } ICM_20948_TIMEBASE_CORRECTION_PLL_t; + + // User Bank 2 Types + typedef struct + { + uint8_t GYRO_SMPLRT_DIV; + } ICM_20948_GYRO_SMPLRT_DIV_t; + + typedef struct + { + uint8_t GYRO_FCHOICE : 1; + uint8_t GYRO_FS_SEL : 2; + uint8_t GYRO_DLPFCFG : 3; + uint8_t reserved_0 : 2; + } ICM_20948_GYRO_CONFIG_1_t; + + typedef struct + { + uint8_t GYRO_AVGCFG : 3; + uint8_t ZGYRO_CTEN : 1; + uint8_t YGYRO_CTEN : 1; + uint8_t XGYRO_CTEN : 1; + uint8_t reserved_0 : 2; + } ICM_20948_GYRO_CONFIG_2_t; + + typedef struct + { + uint8_t XG_OFFS_USER_H; + } ICM_20948_XG_OFFS_USRH_t; + + typedef struct + { + uint8_t XG_OFFS_USER_L; + } ICM_20948_XG_OFFS_USRL_t; + + typedef struct + { + uint8_t YG_OFFS_USER_H; + } ICM_20948_YG_OFFS_USRH_t; + + typedef struct + { + uint8_t YG_OFFS_USER_L; + } ICM_20948_YG_OFFS_USRL_t; + + typedef struct + { + uint8_t ZG_OFFS_USER_H; + } ICM_20948_ZG_OFFS_USRH_t; + + typedef struct + { + uint8_t ZG_OFFS_USER_L; + } ICM_20948_ZG_OFFS_USRL_t; + + typedef struct + { + uint8_t ODR_ALIGN_EN : 1; + uint8_t reserved_0 : 7; + } ICM_20948_ODR_ALIGN_EN_t; + + typedef struct + { + uint8_t ACCEL_SMPLRT_DIV_11_8 : 4; + uint8_t reserved_0 : 4; + } ICM_20948_ACCEL_SMPLRT_DIV_1_t; + + typedef struct + { + uint8_t ACCEL_SMPLRT_DIV_7_0; + } ICM_20948_ACCEL_SMPLRT_DIV_2_t; + + typedef struct + { + uint8_t ACCEL_INTEL_MODE_INT : 1; + uint8_t ACCEL_INTEL_EN : 1; + uint8_t reserved_0 : 6; + } ICM_20948_ACCEL_INTEL_CTRL_t; + + typedef struct + { + uint8_t WOM_THRESHOLD; + } ICM_20948_ACCEL_WOM_THR_t; + + typedef struct + { + uint8_t ACCEL_FCHOICE : 1; + uint8_t ACCEL_FS_SEL : 2; + uint8_t ACCEL_DLPFCFG : 3; + uint8_t reserved_0 : 2; + } ICM_20948_ACCEL_CONFIG_t; + + typedef struct + { + uint8_t DEC3_CFG : 2; + uint8_t AZ_ST_EN : 1; + uint8_t AY_ST_EN : 1; + uint8_t AX_ST_EN : 1; + uint8_t reserved_0 : 3; + } ICM_20948_ACCEL_CONFIG_2_t; + + typedef struct + { + uint8_t EXT_SYNC_SET : 4; + uint8_t WOF_EDGE_INT : 1; + uint8_t WOF_DEGLITCH_EN : 1; + uint8_t reserved_0 : 1; + uint8_t DELAY_TIME_EN : 1; + } ICM_20948_FSYNC_CONFIG_t; + + typedef struct + { + uint8_t TEMP_DLPFCFG : 3; + uint8_t reserved_0 : 5; + } ICM_20948_TEMP_CONFIG_t; + + typedef struct + { + uint8_t REG_LP_DMP_EN : 1; + uint8_t reserved_0 : 7; + } ICM_20948_MOD_CTRL_USR_t; + + // Bank 3 Types + + typedef struct + { + uint8_t I2C_MST_ODR_CONFIG : 4; + uint8_t reserved_0 : 4; + } ICM_20948_I2C_MST_ODR_CONFIG_t; + + typedef struct + { + uint8_t I2C_MST_CLK : 4; + uint8_t I2C_MST_P_NSR : 1; + uint8_t reserved_0 : 2; + uint8_t MULT_MST_EN : 1; + } ICM_20948_I2C_MST_CTRL_t; + + typedef struct + { + uint8_t I2C_PERIPH0_DELAY_EN : 1; + uint8_t I2C_PERIPH1_DELAY_EN : 1; + uint8_t I2C_PERIPH2_DELAY_EN : 1; + uint8_t I2C_PERIPH3_DELAY_EN : 1; + uint8_t I2C_PERIPH4_DELAY_EN : 1; + uint8_t reserved_0 : 2; + uint8_t DELAY_ES_SHADOW : 1; + } ICM_20948_I2C_MST_DELAY_CTRL_t; + + typedef struct + { + uint8_t ID : 7; + uint8_t RNW : 1; + } ICM_20948_I2C_PERIPHX_ADDR_t; + + typedef struct + { + uint8_t REG; + } ICM_20948_I2C_PERIPHX_REG_t; + + typedef struct + { + uint8_t LENG : 4; + uint8_t GRP : 1; + uint8_t REG_DIS : 1; + uint8_t BYTE_SW : 1; + uint8_t EN : 1; + } ICM_20948_I2C_PERIPHX_CTRL_t; + + typedef struct + { + uint8_t DO; + } ICM_20948_I2C_PERIPHX_DO_t; + + typedef struct + { + uint8_t DLY : 5; + uint8_t REG_DIS : 1; + uint8_t INT_EN : 1; + uint8_t EN : 1; + } ICM_20948_I2C_PERIPH4_CTRL_t; + + typedef struct + { + uint8_t DI; + } ICM_20948_I2C_PERIPH4_DI_t; + + // Bank select register! + + typedef struct + { + uint8_t reserved_0 : 4; + uint8_t USER_BANK : 2; + uint8_t reserved_1 : 2; + } ICM_20948_REG_BANK_SEL_t; + +#ifdef __cplusplus +} +#endif /* __cplusplus */ + +#endif /* _ICM_20948_REGISTERS_H_ */ diff --git a/src/util/eMD-SmartMotion-ICM20948-1.1.0-MP/icm20948_img.dmp3a.h_14301 b/src/util/eMD-SmartMotion-ICM20948-1.1.0-MP/icm20948_img.dmp3a.h_14301 new file mode 100644 index 0000000..834203e --- /dev/null +++ b/src/util/eMD-SmartMotion-ICM20948-1.1.0-MP/icm20948_img.dmp3a.h_14301 @@ -0,0 +1,951 @@ + /* bank # 0 */ + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x05, 0x00, 0x00, 0x00, 0x05, 0x00, 0x00, 0x00, 0x05, 0x00, 0x01, 0x00, 0x05, 0x00, 0xff, + 0xff, 0xf7, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, + 0x80, 0x00, 0x80, 0x00, 0x40, 0x00, 0x40, 0x00, 0x20, 0x00, 0x20, 0x00, 0x10, 0x00, 0x10, 0x00, + 0x08, 0x00, 0x08, 0x00, 0x04, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x00, 0x01, 0x00, 0x01, 0x00, + 0x00, 0x80, 0x00, 0x80, 0x00, 0x40, 0x00, 0x40, 0x00, 0x20, 0x00, 0x20, 0x00, 0x10, 0x00, 0x10, + 0x00, 0x08, 0x00, 0x08, 0x00, 0x04, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x00, 0x01, 0x00, 0x01, + /* bank # 1 */ + 0x00, 0x00, 0x03, 0x84, 0x00, 0x00, 0x9c, 0x40, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, + 0x36, 0x66, 0x66, 0x66, 0x00, 0x0f, 0x00, 0x00, 0x13, 0x5c, 0x28, 0xf6, 0x0c, 0xf5, 0xc2, 0x8f, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xff, 0xf8, 0x00, 0x38, + 0x09, 0xed, 0xd1, 0xe8, 0x00, 0x00, 0x68, 0x00, 0x00, 0x01, 0xff, 0xc7, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x01, 0x47, 0xae, 0x14, 0x3e, 0xb8, 0x51, 0xec, 0x00, 0x0f, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x0c, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x15, 0x55, 0x55, 0x55, 0x0a, 0xaa, 0xaa, 0xaa, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe1, 0x00, 0x00, 0x00, 0x01, 0x00, 0x06, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x48, 0xd1, 0x59, 0x3f, 0xb7, 0x2e, 0xa7, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x8e, 0x17, 0x00, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x20, + /* bank # 2 */ + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7f, 0xff, 0x00, 0x00, 0x00, 0x05, 0x21, 0xe9, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x3e, 0x03, 0x30, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x03, 0x00, 0x0a, 0x01, 0x2b, 0x4a, 0xee, + 0x06, 0x54, 0xad, 0x11, 0xe3, 0x07, 0x5c, 0x15, 0x36, 0x2b, 0xd0, 0x26, 0xd0, 0x8c, 0x49, 0xa4, + 0x06, 0x54, 0xad, 0x11, 0x1e, 0x0b, 0xb5, 0x55, 0x38, 0xee, 0x17, 0x50, 0x31, 0x36, 0x3f, 0x03, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 3 */ + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x80, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x00, 0x00, 0x0e, 0x35, 0x75, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x10, 0x00, 0x96, 0x00, 0x3c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0d, 0x72, 0xaa, 0x29, 0xc9, 0x3d, 0x6c, 0x4e, 0x55, 0x16, 0x4c, 0x7f, 0xc4, 0x42, 0x74, 0x97, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x3d, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x31, 0x88, 0x15, 0xe3, 0xa3, 0x40, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0e, 0x70, 0x4b, 0x8c, 0xc5, 0x0a, 0x92, 0xbe, 0x5a, 0x96, 0x91, 0xd2, 0xc1, 0xee, 0xe7, 0x0d, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x02, + 0x00, 0x00, 0x00, 0x14, 0x00, 0x2d, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 4 */ + 0x00, 0x00, 0x00, 0xa3, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x3a, 0x03, 0xe8, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x26, 0x00, 0x00, 0x00, 0x02, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x3f, 0xc1, 0xa7, 0x68, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x33, 0x33, 0x33, 0x33, 0x0c, 0xcc, 0xcc, 0xcd, + 0x00, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x18, + 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x64, 0x87, 0xed, 0x51, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x64, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x01, 0x1d, 0xf4, 0x6a, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x02, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x00, 0x7f, 0xff, 0x00, 0x00, 0x20, 0x00, + /* bank # 5 */ + 0x00, 0x00, 0x9c, 0x40, 0x0c, 0xcc, 0xcc, 0xcd, 0x00, 0x00, 0x07, 0x80, 0x00, 0x02, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3e, 0xb8, 0x51, 0xec, 0x01, 0x47, 0xae, 0x14, + 0x00, 0x00, 0x01, 0x5e, 0x00, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x10, 0x00, 0x00, + 0x00, 0x00, 0x61, 0xa8, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x10, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, 0x2e, 0xe0, 0x00, 0x06, 0x40, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, + 0x03, 0xff, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x33, 0x33, 0x33, 0x33, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0c, 0xcc, 0xcc, 0xcd, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x9d, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 6 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x49, 0x1b, 0x75, + 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x40, 0x00, 0x00, 0x0c, 0xcd, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 7 */ + 0x00, 0x00, 0x50, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x16, 0x00, 0x00, 0x00, 0x00, 0x46, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xd4, 0xc0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, 0x01, 0x3c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 8 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x28, 0x00, 0x00, 0x3a, 0x98, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x01, 0x4e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x47, 0xae, 0x14, 0x4e, 0x40, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0c, 0x00, 0x00, 0x20, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0d, 0x06, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x27, 0x10, + 0x00, 0x00, 0x00, 0x00, 0x4a, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0e, 0xd8, 0x00, 0x00, 0x01, 0x18, 0x00, 0x00, 0x07, 0xd0, + /* bank # 9 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x27, 0x10, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x13, 0x1b, + 0x00, 0x0b, 0xb8, 0x00, 0x00, 0x3c, 0xbf, 0x0f, 0x00, 0x55, 0xce, 0x75, 0x00, 0x00, 0x27, 0x10, + 0x05, 0xb0, 0x5b, 0x05, 0x3a, 0x4f, 0xa4, 0xfa, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x00, 0x00, 0x00, 0x3c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5a, 0x00, 0x1d, 0x20, 0x8a, 0x00, 0x61, 0x93, 0x69, + 0x00, 0x00, 0x01, 0x3c, 0x00, 0x00, 0x4d, 0xf0, 0x00, 0x55, 0xce, 0x75, 0x00, 0x00, 0x02, 0x76, + 0x06, 0x66, 0x66, 0x66, 0x39, 0x99, 0x99, 0x99, 0x10, 0x00, 0x00, 0x00, 0x30, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x0c, 0xcc, 0xcc, 0xcc, 0x33, 0x33, 0x33, 0x33, 0x00, 0x0e, 0x90, 0x45, + 0x00, 0x00, 0x00, 0x00, 0x01, 0xd4, 0x1d, 0x41, 0x3e, 0x2b, 0xe2, 0xbf, 0x3f, 0xf1, 0x6f, 0xbb, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x93, 0x87, 0x00, 0x01, 0x24, 0x92, 0x49, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x13, 0x88, 0x00, 0x98, 0x96, 0x80, 0x08, 0x58, 0x3b, 0x00, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0e, 0xaf, 0x00, 0x00, 0x17, 0x70, 0x00, 0x00, 0x00, 0x01, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 10 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, + 0x3f, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x33, 0x33, 0x33, 0x00, 0x1c, 0xfa, 0x77, + 0x0c, 0x6d, 0x39, 0xe6, 0xcb, 0x6f, 0xda, 0xa6, 0x53, 0xcf, 0xd3, 0x97, 0xc4, 0x53, 0x74, 0x46, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xda, 0x74, 0x0e, 0x3f, 0x25, 0x8b, 0xf2, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x1d, 0x4c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 11 */ + 0x20, 0x00, 0x00, 0x00, 0x3e, 0x2b, 0xe2, 0xbf, 0x3e, 0x14, 0x7a, 0xe2, 0x30, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x13, 0x88, 0x00, 0x00, 0x07, 0xd0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x13, 0x88, 0x3c, 0x23, 0xec, 0x84, + 0x20, 0x00, 0x00, 0x00, 0x01, 0xd4, 0x1d, 0x41, 0x01, 0xeb, 0x85, 0x1e, 0x10, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x13, 0x88, 0x00, 0x00, 0x00, 0x00, 0x34, 0x6c, 0xfc, 0xb2, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, + 0x00, 0x00, 0x17, 0x70, 0x00, 0x00, 0x13, 0x88, 0x00, 0x00, 0x23, 0x28, 0x00, 0x00, 0x00, 0x26, + 0x00, 0x00, 0x00, 0x2f, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x09, 0xc4, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x23, 0x01, 0xeb, 0x85, 0x1e, 0x3e, 0x14, 0x7a, 0xe2, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x2d, 0x02, 0x22, 0x22, 0x22, 0x3d, 0xdd, 0xdd, 0xde, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x24, 0xb8, 0x3d, 0xd1, 0xba, 0x8e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 12 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x83, 0xd6, 0x00, 0x00, 0x83, 0xd6, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, 0x21, + 0x00, 0x20, 0x00, 0x00, 0x00, 0x30, 0xfc, 0xf9, 0x40, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x80, 0x00, + 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x0a, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x33, 0x33, 0x33, 0x00, 0x0c, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x31, 0x88, 0x00, 0x07, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf0, 0xde, 0x9a, 0xf8, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0f, 0x90, 0xb2, 0x83, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf7, 0x21, 0x8c, 0xd5, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0c, 0x6f, 0x39, 0x95, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 13 */ + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x53, 0x44, 0x00, 0x00, 0x53, 0x44, 0x00, 0x01, 0x9a, 0x00, 0x00, 0x01, 0x9a, 0x00, 0x00, + 0x00, 0x00, 0x05, 0x46, 0x00, 0x00, 0x05, 0x46, 0x00, 0x00, 0x00, 0x15, 0x00, 0x00, 0x00, 0x19, + 0x00, 0x00, 0x02, 0x58, 0x00, 0x00, 0x02, 0x58, 0x00, 0x00, 0x00, 0x12, 0x00, 0x00, 0x00, 0x03, + 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x96, 0x00, 0x00, 0x01, 0x2c, 0x00, 0x00, 0x00, 0x96, + 0x00, 0xcf, 0x50, 0xa4, 0x00, 0xcf, 0x50, 0xa4, 0x01, 0x35, 0xd0, 0xa4, 0x01, 0x35, 0xd0, 0xa4, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, + 0x00, 0x0c, 0x80, 0x00, 0x00, 0x0c, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x00, + 0x00, 0x0c, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 14 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x01, 0x7b, 0xab, 0x50, 0x01, 0x2d, 0xb6, 0x48, 0x00, 0x00, 0x16, 0xac, 0x00, 0x22, 0x82, 0x60, + 0x00, 0x00, 0x11, 0x8b, 0x04, 0x4c, 0xcc, 0xb0, 0x00, 0x00, 0x00, 0x14, 0x00, 0x00, 0x16, 0x81, + 0x02, 0x78, 0xfe, 0xe0, 0x03, 0x94, 0x3a, 0xb0, 0x00, 0x10, 0xb4, 0x90, 0x00, 0x00, 0x03, 0x2a, + 0x00, 0x00, 0x25, 0xf6, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x10, 0x00, + 0x08, 0x52, 0xdf, 0x89, 0x05, 0x8c, 0x95, 0x06, 0x01, 0x63, 0x25, 0x41, 0x60, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x7b, 0x47, 0x69, 0x02, 0xe5, 0xdb, 0xae, 0x06, 0xf1, 0x85, 0x78, 0x07, 0xdf, 0xab, 0x88, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 15 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xfe, 0x4c, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x08, 0x66, 0x66, 0x66, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x99, 0x99, 0x9a, 0x00, 0x66, 0x66, 0x66, + 0x00, 0x00, 0x01, 0xf4, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x1e, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x66, 0x66, 0x66, 0x00, 0x04, 0xd4, 0x5e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, 0x28, 0x00, 0x00, 0x00, 0x1e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x66, 0x66, 0x66, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x96, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0xf8, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 16 */ + 0xd8, 0xdc, 0xb8, 0xb0, 0xb4, 0xf3, 0xaa, 0xf8, 0xf9, 0xd1, 0xd9, 0x88, 0x9a, 0xf8, 0xf7, 0x3e, + 0xd8, 0xf3, 0x8a, 0x9a, 0xa7, 0x31, 0xd1, 0xd9, 0xf4, 0x10, 0x36, 0xd8, 0xf3, 0x9f, 0x39, 0xf9, + 0xd1, 0xd9, 0xf4, 0x10, 0x36, 0xd8, 0xf3, 0x8f, 0x9f, 0x08, 0x97, 0x60, 0x8a, 0x21, 0xd1, 0xd9, + 0xf4, 0x10, 0x36, 0xda, 0xf1, 0xff, 0xd8, 0xf1, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xba, 0xb2, + 0xb6, 0xa0, 0x80, 0x90, 0x32, 0x18, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xb8, 0xb0, 0xb4, 0xa4, + 0xdf, 0xa5, 0xde, 0xf3, 0xa8, 0xde, 0xd0, 0xdf, 0xa4, 0x84, 0x9f, 0x24, 0xf2, 0xa9, 0xf8, 0xf9, + 0xd1, 0xda, 0xde, 0xa8, 0xde, 0xdf, 0xdf, 0xdf, 0xd8, 0xf4, 0xb1, 0x8d, 0xf3, 0xa8, 0xd0, 0xb0, + 0xb4, 0x8f, 0xf4, 0xb9, 0xaf, 0xd0, 0xc7, 0xbe, 0xbe, 0xb8, 0xae, 0xd0, 0xf3, 0x9f, 0x75, 0xb2, + 0x86, 0xf4, 0xbe, 0xbe, 0xb9, 0xaf, 0xd0, 0xc3, 0xf1, 0xbe, 0xb8, 0xb0, 0xa3, 0xde, 0xdf, 0xdf, + 0xdf, 0xf2, 0xa3, 0x81, 0xc0, 0x80, 0xcd, 0xc7, 0xcf, 0xbc, 0xbd, 0xb4, 0xf1, 0xa3, 0x8d, 0x93, + 0x20, 0xfd, 0x3f, 0x88, 0x6e, 0x76, 0x7e, 0x8d, 0x93, 0xbe, 0xa2, 0x20, 0xfd, 0x31, 0xa0, 0x2c, + 0xfd, 0x32, 0x34, 0xfd, 0x32, 0x3c, 0xfd, 0x32, 0xbe, 0xb9, 0xac, 0x8d, 0x20, 0xb8, 0xbe, 0xbe, + 0xbc, 0xa2, 0x86, 0x9d, 0x08, 0xfd, 0x0f, 0xbc, 0xbc, 0xbc, 0xa3, 0x82, 0x93, 0x01, 0xa9, 0x83, + 0x9e, 0x0e, 0x16, 0x1e, 0xbe, 0xbe, 0xbe, 0xbc, 0xa5, 0x8b, 0x99, 0x2c, 0x54, 0x7c, 0xbc, 0xbc, + 0x85, 0x93, 0xba, 0xa5, 0x2d, 0x55, 0x7d, 0xb8, 0xa5, 0x9d, 0x2c, 0xfd, 0x37, 0x4c, 0xfd, 0x37, + 0x6c, 0xfd, 0x37, 0xf5, 0xa5, 0x85, 0x9f, 0x34, 0x54, 0x74, 0xbd, 0xbd, 0xbd, 0xb1, 0xb6, 0xba, + /* bank # 17 */ + 0x83, 0x95, 0xa5, 0xf1, 0x0e, 0x16, 0x1e, 0xb2, 0xa7, 0x85, 0x95, 0x2a, 0xf0, 0x50, 0x78, 0x87, + 0x93, 0xf1, 0x01, 0xda, 0xa5, 0xdf, 0xdf, 0xdf, 0xd8, 0xa4, 0xdf, 0xdf, 0xdf, 0xb0, 0x80, 0xf2, + 0xa4, 0xc3, 0xcb, 0xc5, 0xf1, 0xb1, 0x8e, 0x94, 0xa4, 0x0e, 0x16, 0x1e, 0xb2, 0x86, 0xbe, 0xa0, + 0x2c, 0x34, 0x3c, 0xbd, 0xbd, 0xb4, 0x96, 0xb8, 0xa1, 0x2c, 0x34, 0x3c, 0xbd, 0xbd, 0xb6, 0x94, + 0xbe, 0xa6, 0x2c, 0xfd, 0x35, 0x34, 0xfd, 0x35, 0x3c, 0xfd, 0x35, 0xbc, 0xb2, 0x8e, 0x94, 0xb8, + 0xbe, 0xbe, 0xa6, 0x2d, 0x55, 0x7d, 0xba, 0xa4, 0x2d, 0x55, 0x7d, 0xb8, 0xb0, 0xb4, 0xa6, 0x8f, + 0x96, 0x2e, 0x36, 0x3e, 0xbc, 0xbc, 0xbc, 0xbd, 0xa6, 0x86, 0x9f, 0xf5, 0x34, 0x54, 0x74, 0xbc, + 0xbe, 0xf1, 0x90, 0xfc, 0xc3, 0x00, 0xd9, 0xf4, 0x11, 0xdf, 0xd8, 0xf3, 0xa0, 0xdf, 0xf1, 0xbc, + 0x86, 0x91, 0xa9, 0x2d, 0x55, 0x7d, 0xbc, 0xbc, 0xbc, 0xa9, 0x80, 0x90, 0xfc, 0x51, 0x00, 0x10, + 0xfc, 0x51, 0x00, 0x10, 0xfc, 0x51, 0x00, 0x10, 0xfc, 0xc1, 0x04, 0xd9, 0xf2, 0xa0, 0xdf, 0xf4, + 0x11, 0xdf, 0xd8, 0xf6, 0xa0, 0xfa, 0x80, 0x90, 0x38, 0xf3, 0xde, 0xda, 0xf8, 0xf4, 0x11, 0xdf, + 0xd8, 0xf1, 0xbd, 0x95, 0xfc, 0xc1, 0x04, 0xd9, 0xbd, 0xbd, 0xbd, 0xf4, 0x11, 0xdf, 0xd8, 0xf6, + 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xbe, 0xb5, 0xa7, 0x84, 0x92, 0x1a, 0xf8, 0xf9, 0xd1, + 0xdb, 0x84, 0x93, 0xf7, 0x6a, 0xb6, 0x87, 0x96, 0xf3, 0x09, 0xff, 0xda, 0xbc, 0xbd, 0xbe, 0xd8, + 0xf1, 0xbc, 0xbc, 0xbc, 0xf6, 0xb0, 0x82, 0xb4, 0x97, 0xb8, 0xa9, 0x02, 0xf7, 0x02, 0xf1, 0xbc, + 0x89, 0x99, 0xa7, 0x04, 0xfd, 0x37, 0xa8, 0xdf, 0x87, 0x98, 0xa7, 0xfc, 0x3d, 0x00, 0x50, 0xf8, + /* bank # 18 */ + 0xf9, 0xd1, 0xd9, 0xa8, 0xdf, 0xf9, 0xd8, 0xf6, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbe, 0xbe, + 0xbe, 0xb7, 0xa7, 0x81, 0x9a, 0x0b, 0xb4, 0x87, 0x9f, 0x1a, 0xf8, 0xf9, 0xd1, 0xbb, 0x81, 0xaa, + 0xc1, 0xd9, 0xf4, 0x12, 0x47, 0xd8, 0xf6, 0xb8, 0xa7, 0x1a, 0xf9, 0xd9, 0xf4, 0x12, 0x47, 0xd8, + 0x8a, 0xf3, 0xbb, 0xaa, 0xc0, 0xc3, 0xb3, 0xaa, 0x8a, 0x9d, 0x1a, 0xfd, 0x1e, 0xb7, 0x9a, 0x08, + 0xb8, 0xb0, 0xb4, 0xa5, 0x85, 0x9d, 0x00, 0xd8, 0xf3, 0xb9, 0xb2, 0xa9, 0x80, 0xcd, 0xf2, 0xc4, + 0xc5, 0xba, 0xf3, 0xa0, 0xd0, 0xde, 0xb1, 0xb4, 0xf7, 0xa7, 0x89, 0x91, 0x72, 0x89, 0x91, 0x47, + 0xb6, 0x97, 0x4a, 0xb9, 0xf2, 0xa9, 0xd0, 0xfa, 0xf9, 0xd1, 0xd9, 0xf4, 0x12, 0x75, 0xd8, 0xf3, + 0xba, 0xa7, 0xf9, 0xdb, 0xfb, 0xd9, 0xf1, 0xb9, 0xb0, 0x81, 0xa9, 0xc3, 0xf2, 0xc5, 0xf3, 0xba, + 0xa0, 0xd0, 0xf8, 0xd8, 0xf1, 0xb1, 0x89, 0xa7, 0xdf, 0xdf, 0xdf, 0xf2, 0xa7, 0xc3, 0xcb, 0xc5, + 0xf1, 0xb2, 0x87, 0xb8, 0xbe, 0xbe, 0xbe, 0xab, 0xc2, 0xc5, 0xc7, 0xbe, 0xb5, 0xb9, 0x97, 0xa5, + 0x22, 0xf0, 0x48, 0x70, 0x3c, 0x98, 0x40, 0x68, 0x34, 0x58, 0x99, 0x60, 0xf1, 0xbc, 0xb3, 0x8e, + 0x95, 0xaa, 0x25, 0x4d, 0x75, 0xbc, 0xbc, 0xbc, 0xb8, 0xb0, 0xb4, 0xa7, 0x88, 0x9f, 0xf7, 0x5a, + 0xf9, 0xda, 0xf3, 0xa8, 0xf8, 0x88, 0x9d, 0xd0, 0x7c, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, 0x52, 0xf9, + 0xda, 0xf3, 0xa8, 0x88, 0x9c, 0xd0, 0xdf, 0x60, 0x68, 0x70, 0x78, 0x9d, 0x60, 0x68, 0x70, 0x78, + 0x9e, 0x70, 0x78, 0x9f, 0x70, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, 0x42, 0xf9, 0xba, 0xa0, 0xd0, 0xf3, + 0xd9, 0xde, 0xd8, 0xf8, 0xf9, 0xd1, 0xb8, 0xda, 0xa8, 0x88, 0x9e, 0xd0, 0x64, 0x68, 0x9f, 0x60, + /* bank # 19 */ + 0xd8, 0xa8, 0x84, 0x98, 0xd0, 0xf7, 0x7e, 0xf1, 0xb2, 0xb6, 0xba, 0x85, 0x91, 0xa7, 0xf4, 0x75, + 0xa8, 0xf4, 0x75, 0xc0, 0xf1, 0x84, 0x91, 0xa7, 0xf4, 0x75, 0xa8, 0xf0, 0xa2, 0x87, 0x0d, 0x20, + 0x59, 0x70, 0x15, 0x38, 0x40, 0x69, 0xa4, 0xf1, 0x62, 0xf0, 0x19, 0x31, 0x48, 0xb8, 0xb1, 0xb4, + 0xf1, 0xa6, 0x80, 0xc6, 0xf4, 0xb0, 0x81, 0xf3, 0xa7, 0xc6, 0xb1, 0x8f, 0x97, 0xf7, 0x02, 0xf9, + 0xda, 0xf4, 0x13, 0x7f, 0xd8, 0xb0, 0xf7, 0xa7, 0x88, 0x9f, 0x52, 0xf9, 0xd9, 0xf4, 0x13, 0x78, + 0xd8, 0xf1, 0xb2, 0xb6, 0xa6, 0x82, 0x92, 0x2a, 0xf0, 0x50, 0xfd, 0x08, 0xf1, 0xa7, 0x84, 0x94, + 0x02, 0xfd, 0x08, 0xb0, 0xb4, 0x86, 0x97, 0x00, 0xb1, 0xba, 0xa7, 0x81, 0x61, 0xd9, 0xf4, 0x13, + 0x97, 0xd8, 0xf1, 0x41, 0xda, 0xf4, 0x13, 0x97, 0xd8, 0xf1, 0xb8, 0xb2, 0xa6, 0x82, 0xc0, 0xd8, + 0xf1, 0xb0, 0xb6, 0x86, 0x92, 0xa7, 0x16, 0xfd, 0x04, 0x0f, 0xfd, 0x04, 0xba, 0x87, 0x91, 0xa7, + 0xf4, 0x75, 0xb6, 0xb2, 0xf4, 0x75, 0xc0, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xbd, 0xbd, 0xbd, 0xb2, + 0xba, 0x84, 0xa7, 0xc3, 0xc5, 0xc7, 0xb2, 0xbc, 0xbc, 0xbc, 0xb6, 0x87, 0x91, 0xaf, 0xf4, 0x75, + 0xa8, 0xa0, 0x8f, 0xf1, 0x0b, 0xf0, 0x20, 0x59, 0x70, 0x15, 0x38, 0x40, 0x69, 0x64, 0x19, 0x31, + 0x48, 0xf1, 0x80, 0x90, 0xaf, 0x6e, 0xfd, 0x04, 0x67, 0xfd, 0x04, 0x8f, 0x91, 0xa7, 0xf4, 0x75, + 0xb6, 0xf4, 0x75, 0xc0, 0xf1, 0xbe, 0xbc, 0xbd, 0xf7, 0xbe, 0xb0, 0xb4, 0xba, 0x88, 0x9e, 0xa3, + 0x6a, 0x9f, 0x66, 0xf0, 0xb1, 0xb5, 0xb9, 0x8a, 0x9a, 0xa2, 0x2c, 0x50, 0x78, 0xb2, 0xb9, 0x8a, + 0xaf, 0xc0, 0xc3, 0xc5, 0xc7, 0x89, 0xad, 0xd0, 0xc4, 0xc7, 0x83, 0xa1, 0xc2, 0xc5, 0xba, 0xbc, + /* bank # 20 */ + 0xbc, 0xbc, 0xb2, 0x81, 0xa2, 0xc0, 0xc3, 0xc5, 0xc7, 0xbc, 0xbc, 0xbd, 0xf4, 0x74, 0x9c, 0xf3, + 0xba, 0xa3, 0xfa, 0xf9, 0xd1, 0xd9, 0xf4, 0x14, 0x33, 0xd8, 0x74, 0xad, 0xbe, 0xbe, 0xbe, 0xba, + 0xb1, 0x82, 0xa3, 0xd0, 0xc7, 0xa9, 0xd0, 0x8d, 0xc4, 0xc7, 0xa3, 0x81, 0xc1, 0xc3, 0xf3, 0xa6, + 0x8d, 0xc2, 0xbe, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xba, 0xb1, 0xaa, 0x8f, 0xc0, 0xc3, 0xc5, 0xc7, + 0xbe, 0xbc, 0xbc, 0xbc, 0xb2, 0xb9, 0x88, 0xaf, 0xc0, 0xc3, 0xc5, 0xc7, 0x80, 0xad, 0xd0, 0xc0, + 0xc3, 0x89, 0xa1, 0xc0, 0xc3, 0xba, 0x81, 0xa2, 0xc0, 0xc3, 0xc5, 0xc7, 0xbc, 0xf4, 0x74, 0x9c, + 0xf3, 0xba, 0xa3, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x14, 0x84, 0xd8, 0x74, 0xad, 0xbe, 0xbe, 0xbe, + 0xb8, 0xb1, 0x82, 0xa7, 0xd0, 0xc7, 0xba, 0xa0, 0x8d, 0xc4, 0xc7, 0xa9, 0x81, 0xc0, 0xc3, 0xf3, + 0xa5, 0x8d, 0xc2, 0xbe, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xba, 0xb1, 0xa8, 0x8f, 0xc0, 0xc3, 0xc5, + 0xc7, 0xbe, 0xf3, 0xba, 0xb2, 0xb6, 0xa3, 0x83, 0x93, 0x08, 0xf9, 0xd9, 0xf4, 0x15, 0x02, 0xd8, + 0xf0, 0xb8, 0xb0, 0xa3, 0x85, 0x94, 0x04, 0x28, 0x50, 0x78, 0xf1, 0xb4, 0x84, 0x93, 0x69, 0xd9, + 0xb6, 0xa5, 0x8d, 0x94, 0x20, 0x2c, 0x34, 0x3c, 0xb4, 0xa4, 0xde, 0xdf, 0xf8, 0xf4, 0x14, 0xcc, + 0xd8, 0xf1, 0xa4, 0xf8, 0xa3, 0x84, 0x94, 0x41, 0xd9, 0xa4, 0xdf, 0xf8, 0xd8, 0xf1, 0x94, 0xfc, + 0xc1, 0x04, 0xd9, 0xa4, 0xfb, 0xa3, 0x86, 0xc0, 0xb1, 0x82, 0x9e, 0x06, 0xfd, 0x1e, 0xa6, 0x81, + 0x96, 0x42, 0x93, 0xf0, 0x68, 0xb0, 0xa3, 0xf1, 0x83, 0x96, 0x01, 0xf5, 0x83, 0x93, 0x00, 0xa6, + 0x86, 0x96, 0xf0, 0x34, 0x83, 0x18, 0xf1, 0xa1, 0x8d, 0x68, 0xa3, 0x81, 0x9b, 0xdb, 0x19, 0x8b, + /* bank # 21 */ + 0xa1, 0xc6, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xd8, 0xf7, 0xb8, + 0xb4, 0xb0, 0xa7, 0x9d, 0x88, 0x72, 0xf9, 0xbc, 0xbd, 0xbe, 0xd9, 0xf4, 0x17, 0xa1, 0xd8, 0xf2, + 0xb8, 0xad, 0xf8, 0xf9, 0xd1, 0xda, 0xde, 0xba, 0xa1, 0xde, 0xae, 0xde, 0xf8, 0xd8, 0xb2, 0x81, + 0xbe, 0xbe, 0xb9, 0xaf, 0xd0, 0xc1, 0xbc, 0xbc, 0xbd, 0xbd, 0xb1, 0xb4, 0xf1, 0xac, 0x8c, 0x92, + 0x0a, 0x18, 0xb5, 0xaf, 0x8c, 0x9d, 0x41, 0xdb, 0x9c, 0x11, 0x8e, 0xad, 0xc0, 0xbe, 0xbe, 0xba, + 0xae, 0xc3, 0xc5, 0xc7, 0x8d, 0xa8, 0xc6, 0xc7, 0xc7, 0xc7, 0xa6, 0xde, 0xdf, 0xdf, 0xdf, 0xa5, + 0xd0, 0xde, 0xdf, 0xbe, 0xbe, 0xd8, 0xb9, 0xac, 0xdf, 0xaf, 0x8d, 0x9c, 0x11, 0xd9, 0x8c, 0xc5, + 0xda, 0xc1, 0xd8, 0xaf, 0x8f, 0x21, 0xf5, 0x9f, 0x00, 0xf1, 0x8c, 0x9c, 0x45, 0xd9, 0x8f, 0xac, + 0xc1, 0xd8, 0xf2, 0xaf, 0xdf, 0xf8, 0xf8, 0xdf, 0xf8, 0xf8, 0xf8, 0xaf, 0x8f, 0x9f, 0x59, 0xd1, + 0xdb, 0xf1, 0x8c, 0x9c, 0x31, 0xf2, 0x8f, 0xaf, 0xd0, 0xc3, 0xd8, 0xaf, 0x8f, 0x9f, 0x39, 0xd1, + 0xdb, 0xf1, 0x8c, 0x9c, 0x69, 0xf2, 0x8f, 0xaf, 0xd0, 0xc5, 0xd8, 0x8f, 0xbe, 0xbe, 0xba, 0xa1, + 0xc6, 0xbc, 0xbc, 0xbd, 0xbd, 0xf2, 0xb1, 0xb5, 0xb9, 0xae, 0xf9, 0xda, 0xf4, 0x17, 0x74, 0xd8, + 0xf2, 0x8e, 0xc2, 0xf1, 0xb2, 0x80, 0x9a, 0xf5, 0xaf, 0x24, 0xd9, 0xf4, 0x17, 0x74, 0xd8, 0xf5, + 0x44, 0xd9, 0xf4, 0x17, 0x74, 0xd8, 0xf5, 0x64, 0xd9, 0xf4, 0x17, 0x74, 0xd8, 0xf1, 0xb1, 0xb6, + 0x8b, 0x90, 0xaf, 0x2d, 0x55, 0x7d, 0xb5, 0x8c, 0x9f, 0xad, 0x0e, 0x16, 0x1e, 0x8b, 0x9d, 0xab, + 0x2c, 0x54, 0x7c, 0x8d, 0x9f, 0xaa, 0x2e, 0x56, 0x7e, 0x8a, 0x9c, 0xaa, 0x2c, 0x54, 0x7c, 0x9b, + /* bank # 22 */ + 0xac, 0x26, 0x46, 0x66, 0xaf, 0x8d, 0x9d, 0x00, 0x9c, 0x0d, 0xdb, 0x11, 0x8f, 0x19, 0xf4, 0x16, + 0x14, 0xd8, 0x17, 0x74, 0xd8, 0xf1, 0xb2, 0x81, 0xb6, 0x90, 0xaf, 0x2d, 0x55, 0x7d, 0xb1, 0x8f, + 0xb5, 0x9f, 0xaf, 0xf5, 0x2c, 0x54, 0x7c, 0xf1, 0xb2, 0x8c, 0x9f, 0xad, 0x6d, 0xdb, 0x71, 0x79, + 0xf4, 0x16, 0x42, 0xd8, 0xf3, 0xba, 0xa1, 0xde, 0xf8, 0xf1, 0x80, 0xa1, 0xc3, 0xc5, 0xc7, 0xf4, + 0x16, 0x51, 0xd8, 0xf3, 0xb6, 0xba, 0x91, 0xfc, 0xc0, 0x28, 0xda, 0xa1, 0xf8, 0xd9, 0xf4, 0x17, + 0x74, 0xd8, 0xf3, 0xb9, 0xae, 0xf8, 0xf9, 0xd1, 0xd9, 0xf8, 0xf4, 0x17, 0x74, 0xd8, 0xf1, 0xba, + 0xb1, 0xb5, 0xa0, 0x8b, 0x93, 0x3e, 0x5e, 0x7e, 0xab, 0x83, 0xc0, 0xc5, 0xb2, 0xb6, 0xa3, 0x87, + 0xc0, 0xc3, 0xc5, 0xc7, 0xa2, 0x88, 0xc0, 0xc3, 0xc5, 0xc7, 0xa4, 0x86, 0xc0, 0xc3, 0xc5, 0xc7, + 0xa5, 0x85, 0xc4, 0xc7, 0xac, 0x8d, 0xc0, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xb9, 0xb1, 0xb5, + 0xad, 0xd0, 0xde, 0xaf, 0x8c, 0x9c, 0x41, 0xd9, 0xf4, 0x16, 0xc0, 0xd8, 0xf1, 0xf8, 0xf9, 0xd1, + 0xd9, 0xf4, 0x16, 0xd9, 0xd8, 0xf1, 0xaf, 0x8d, 0x9c, 0x31, 0xda, 0x8c, 0xc5, 0xd9, 0xc3, 0xd8, + 0xaf, 0x8f, 0x21, 0xf5, 0x9f, 0x00, 0xf1, 0xad, 0xd0, 0xb0, 0x82, 0x9f, 0x02, 0xf4, 0x16, 0xd9, + 0xd8, 0xf1, 0xaf, 0x8d, 0x9c, 0x31, 0xd9, 0x8c, 0xc5, 0xda, 0xc3, 0xd8, 0xaf, 0x8f, 0x21, 0xf5, + 0x9f, 0x00, 0xf1, 0xad, 0xd0, 0xb0, 0x83, 0x9f, 0x02, 0xd8, 0xf1, 0xb1, 0x8c, 0xad, 0xc1, 0xbe, + 0xbe, 0xbd, 0xbd, 0xba, 0xb6, 0xac, 0x8d, 0x9c, 0x40, 0xbc, 0xbc, 0xb2, 0xa0, 0xde, 0xf8, 0xf8, + 0xf8, 0xf8, 0xf8, 0xfd, 0x0f, 0xf5, 0xaf, 0x88, 0x98, 0x00, 0x2c, 0x54, 0x7c, 0xf1, 0xaf, 0x80, + /* bank # 23 */ + 0x9f, 0x01, 0xdb, 0x09, 0x11, 0x19, 0xf4, 0x17, 0x13, 0xd8, 0xf2, 0xa1, 0xf8, 0xf9, 0xd1, 0xda, + 0xf1, 0xac, 0xde, 0xd8, 0xf3, 0xae, 0xde, 0xf8, 0xf4, 0x1a, 0x8e, 0xd8, 0xf1, 0xa7, 0x83, 0xc0, + 0xc3, 0xc5, 0xc7, 0xa8, 0x82, 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x84, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, + 0x85, 0xd0, 0xc0, 0xc3, 0x8d, 0x9d, 0xaf, 0x39, 0xd9, 0xf4, 0x17, 0x74, 0xd8, 0xf1, 0x83, 0xb5, + 0x9e, 0xae, 0x34, 0xfd, 0x0a, 0x54, 0xfd, 0x0a, 0x74, 0xfd, 0x0a, 0xf2, 0xa1, 0xde, 0xf8, 0xf8, + 0xf8, 0xf1, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xb9, 0xb1, 0xb5, 0x8c, 0xad, 0xc0, 0xaf, 0x9c, + 0x11, 0xd9, 0xae, 0xc0, 0xbc, 0xbc, 0xb2, 0x8e, 0xc3, 0xc5, 0xc7, 0xbc, 0xbc, 0xd8, 0xbe, 0xbe, + 0xbc, 0xbc, 0xbd, 0xbd, 0xd8, 0xf2, 0xba, 0xb2, 0xb5, 0xaf, 0x81, 0x97, 0x01, 0xd1, 0xb9, 0xa7, + 0xc0, 0xda, 0xf4, 0x17, 0x8c, 0xd8, 0xf2, 0xba, 0xae, 0xf8, 0xf9, 0xd1, 0xda, 0xf3, 0xbe, 0xbe, + 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xb8, 0xb0, 0xb4, 0xa5, 0x85, 0x9c, 0x08, 0xbe, 0xbc, + 0xbd, 0xd8, 0xf7, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbb, 0xb4, 0xb0, 0xaf, 0x9e, 0x88, 0x62, + 0xf9, 0xbc, 0xbd, 0xd9, 0xf4, 0x19, 0xe7, 0xd8, 0xf1, 0xbc, 0xbc, 0xbc, 0xb1, 0x85, 0xba, 0xb5, + 0xa0, 0x98, 0x06, 0x26, 0x46, 0xbc, 0xb9, 0xb3, 0xb6, 0xf1, 0xaf, 0x81, 0x90, 0x2d, 0x55, 0x7d, + 0xb1, 0xb5, 0xaf, 0x8f, 0x9f, 0xf5, 0x2c, 0x54, 0x7c, 0xf1, 0xbb, 0xaf, 0x86, 0x9f, 0x69, 0xdb, + 0x71, 0x79, 0xda, 0xf3, 0xa0, 0xdf, 0xf8, 0xf1, 0xa1, 0xde, 0xf2, 0xf8, 0xd8, 0xb3, 0xb7, 0xf1, + 0x8c, 0x9b, 0xaf, 0x19, 0xd9, 0xac, 0xde, 0xf3, 0xa0, 0xdf, 0xf8, 0xd8, 0xaf, 0x80, 0x90, 0x69, + /* bank # 24 */ + 0xd9, 0xa0, 0xfa, 0xf1, 0xb2, 0x80, 0xa1, 0xc3, 0xc5, 0xc7, 0xf2, 0xa0, 0xd0, 0xdf, 0xf8, 0xf4, + 0x19, 0xd1, 0xd8, 0xf2, 0xa0, 0xd0, 0xdf, 0xf1, 0xbc, 0xbc, 0xbc, 0xb1, 0xad, 0x8a, 0x9e, 0x26, + 0x46, 0x66, 0xbc, 0xb3, 0xf3, 0xa2, 0xde, 0xf8, 0xf4, 0x1a, 0x17, 0xd8, 0xf1, 0xaa, 0x8d, 0xc1, + 0xf2, 0xa1, 0xf8, 0xf9, 0xd1, 0xda, 0xf4, 0x18, 0x5c, 0xd8, 0xf1, 0xaf, 0x8a, 0x9a, 0x21, 0x8f, + 0x90, 0xf5, 0x10, 0xda, 0xf4, 0x18, 0x5c, 0xd8, 0xf1, 0x91, 0xfc, 0xc0, 0x04, 0xd9, 0xf4, 0x18, + 0xa3, 0xd8, 0xf3, 0xa1, 0xde, 0xf8, 0xa0, 0xdf, 0xf8, 0xf4, 0x19, 0xd1, 0xf3, 0x91, 0xfc, 0xc0, + 0x07, 0xd9, 0xf4, 0x18, 0xa3, 0xd8, 0xf1, 0xaf, 0xb1, 0x84, 0x9c, 0x01, 0xb3, 0xb5, 0x80, 0x97, + 0xdb, 0xf3, 0x21, 0xb9, 0xa7, 0xd9, 0xf8, 0xf4, 0x18, 0xa3, 0xd8, 0xf3, 0xb9, 0xa7, 0xde, 0xf8, + 0xbb, 0xf1, 0xa3, 0x87, 0xc0, 0xc3, 0xc5, 0xc7, 0xa4, 0x88, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, 0x89, + 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x86, 0xc4, 0xc7, 0xa1, 0x82, 0xc3, 0xc5, 0xc7, 0xf3, 0xa1, 0xde, + 0xf4, 0x19, 0xe7, 0xd8, 0xf1, 0xbb, 0xb3, 0xb7, 0xa1, 0xf8, 0xf9, 0xd1, 0xda, 0xf2, 0xa0, 0xd0, + 0xdf, 0xf8, 0xd8, 0xf1, 0xb9, 0xb1, 0xb6, 0xa8, 0x87, 0x90, 0x2d, 0x55, 0x7d, 0xf5, 0xb5, 0xa8, + 0x88, 0x98, 0x2c, 0x54, 0x7c, 0xf1, 0xaf, 0x86, 0x98, 0x29, 0xdb, 0x31, 0x39, 0xf4, 0x19, 0xe7, + 0xd8, 0xf1, 0xb3, 0xb6, 0xa7, 0x8a, 0x90, 0x4c, 0x54, 0x5c, 0xba, 0xa0, 0x81, 0x90, 0x2d, 0x55, + 0x7d, 0xbb, 0xf2, 0xa2, 0xf8, 0xf9, 0xd1, 0xda, 0xde, 0xf4, 0x19, 0xe7, 0xd8, 0xf1, 0xba, 0xb0, + 0xab, 0x8f, 0xc0, 0xc7, 0xb3, 0xa3, 0x83, 0xc0, 0xc3, 0xc5, 0xc7, 0xa2, 0x84, 0xc0, 0xc3, 0xc5, + /* bank # 25 */ + 0xc7, 0xa4, 0x85, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, 0x86, 0xc0, 0xc3, 0xac, 0x8c, 0xc2, 0xf3, 0xae, + 0xde, 0xf8, 0xf8, 0xf4, 0x1a, 0x8e, 0xd8, 0xf1, 0xb2, 0xbb, 0xa3, 0x83, 0xc0, 0xc3, 0xc5, 0xc7, + 0xa4, 0x82, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, 0x84, 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x85, 0xc0, 0xc3, + 0xac, 0x8c, 0xc4, 0xb3, 0xb7, 0xaf, 0x85, 0x95, 0x56, 0xfd, 0x0f, 0x86, 0x96, 0x06, 0xfd, 0x0f, + 0xf0, 0x84, 0x9f, 0xaf, 0x4c, 0x70, 0xfd, 0x0f, 0xf1, 0x86, 0x96, 0x2e, 0xfd, 0x0f, 0x84, 0x9f, + 0x72, 0xfd, 0x0f, 0xdf, 0xaf, 0x2c, 0x54, 0x7c, 0xaf, 0x8c, 0x69, 0xdb, 0x71, 0x79, 0x8b, 0x9c, + 0x61, 0xf4, 0x19, 0x67, 0xda, 0x19, 0xe7, 0xd8, 0xf1, 0xab, 0x83, 0x91, 0x28, 0xfd, 0x05, 0x54, + 0xfd, 0x05, 0x7c, 0xfd, 0x05, 0xb8, 0xbd, 0xbd, 0xbd, 0xb5, 0xa3, 0x8b, 0x95, 0x05, 0x2d, 0x55, + 0xbd, 0xb4, 0xbb, 0xad, 0x8e, 0x93, 0x0e, 0x16, 0x1e, 0xb7, 0xf3, 0xa2, 0xde, 0xf8, 0xf8, 0xf4, + 0x1a, 0x17, 0xd8, 0xf2, 0xa1, 0xf8, 0xf9, 0xd1, 0xd9, 0xf1, 0xaf, 0x8d, 0x9a, 0x01, 0xf5, 0x8f, + 0x90, 0xdb, 0x00, 0xf4, 0x19, 0xe7, 0xda, 0xf1, 0xaa, 0x8d, 0xc0, 0xae, 0x8b, 0xc1, 0xc3, 0xc5, + 0xa1, 0xde, 0xa7, 0x83, 0xc0, 0xc3, 0xc5, 0xc7, 0xa8, 0x84, 0xc0, 0xc3, 0xc5, 0xc7, 0xa9, 0x85, + 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x86, 0xd0, 0xc0, 0xc3, 0xa2, 0x81, 0xc3, 0xc5, 0xc7, 0xf4, 0x19, + 0xe7, 0xf1, 0xbb, 0xb3, 0xa3, 0xde, 0xdf, 0xdf, 0xdf, 0xa4, 0x8c, 0xc4, 0xc5, 0xc5, 0xc5, 0xa5, + 0xde, 0xdf, 0xdf, 0xdf, 0xa6, 0xde, 0xdf, 0xd8, 0xf3, 0xb9, 0xae, 0xdf, 0xba, 0xae, 0xde, 0xbb, + 0xa2, 0xde, 0xbe, 0xbc, 0xb3, 0xbd, 0xb7, 0xaf, 0x8e, 0x9c, 0x01, 0xd1, 0xac, 0xc0, 0xd9, 0xae, + /* bank # 26 */ + 0xde, 0xd8, 0xf1, 0xb1, 0x83, 0xb9, 0xa7, 0xd0, 0xc4, 0xb8, 0xae, 0xde, 0xbe, 0xbe, 0xbe, 0xbb, + 0xbc, 0xbc, 0xbc, 0xb3, 0xbd, 0xbd, 0xbd, 0xd8, 0xf3, 0xa2, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x1a, + 0x8c, 0xd8, 0xf5, 0xad, 0x8d, 0x9d, 0x2c, 0x54, 0x7c, 0xf1, 0xaf, 0x49, 0xda, 0xc3, 0xc5, 0xd9, + 0xc5, 0xc3, 0xd8, 0xaf, 0x9f, 0x69, 0xd0, 0xda, 0xc7, 0xd9, 0x8f, 0xc3, 0x8d, 0xaf, 0xc7, 0xd8, + 0xb9, 0xa9, 0x8f, 0x9f, 0xf0, 0x54, 0x78, 0xf1, 0xfd, 0x0f, 0xa6, 0xb1, 0x89, 0xc2, 0xb3, 0xaf, + 0x8f, 0x9f, 0x2e, 0xfd, 0x11, 0xb1, 0xb5, 0xa9, 0x89, 0x9f, 0x2c, 0xf3, 0xae, 0xdf, 0xf8, 0xf8, + 0xf4, 0x1c, 0x43, 0xd8, 0xf1, 0xad, 0x86, 0x99, 0x06, 0xfd, 0x10, 0xdf, 0xf8, 0xfd, 0x0f, 0xad, + 0x8d, 0x9d, 0x4c, 0xbb, 0xb3, 0xad, 0x8f, 0x9d, 0x2a, 0xfd, 0x0f, 0xb7, 0x92, 0xfc, 0xc0, 0x04, + 0xd9, 0xf4, 0x18, 0x2b, 0xd8, 0xfc, 0xc0, 0x08, 0xd9, 0xf4, 0x19, 0x92, 0xd8, 0xf1, 0xd8, 0xf3, + 0xba, 0xb2, 0xb6, 0xae, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x1c, 0x41, 0xd8, 0xf1, 0xaf, 0xde, 0xf9, + 0xfd, 0x0f, 0x80, 0x90, 0x2c, 0x54, 0x7c, 0xa0, 0x2a, 0xf0, 0x50, 0x78, 0xfd, 0x0f, 0xf1, 0xa2, + 0x82, 0x9c, 0x00, 0x24, 0x44, 0x64, 0xa9, 0x8f, 0x94, 0xf0, 0x04, 0xfd, 0x0f, 0x0c, 0x30, 0xfd, + 0x0f, 0x1c, 0x95, 0x20, 0x48, 0xfd, 0x0f, 0xf1, 0x99, 0xc1, 0x2c, 0x54, 0x7c, 0xaa, 0x82, 0x99, + 0x02, 0xfd, 0x0f, 0x2e, 0xfd, 0x0f, 0x56, 0xfd, 0x0f, 0x7e, 0xfd, 0x0f, 0xac, 0x83, 0x9f, 0xf0, + 0x04, 0x28, 0x50, 0x78, 0xfd, 0x0f, 0x8c, 0x90, 0xf1, 0x21, 0xf5, 0x8c, 0x9c, 0x2c, 0xf1, 0xaf, + 0xde, 0xf1, 0x89, 0xaf, 0x9f, 0xfc, 0xc0, 0x00, 0xd9, 0xc1, 0x8a, 0xc1, 0x82, 0xc1, 0xd8, 0xfc, + /* bank # 27 */ + 0xc0, 0x04, 0xd9, 0xc3, 0x8a, 0xc3, 0x82, 0xc3, 0xd8, 0xfc, 0xc0, 0x08, 0xd9, 0xc5, 0x8a, 0xc5, + 0x82, 0xc5, 0xd8, 0xfc, 0xc0, 0x0c, 0xd9, 0xc7, 0x8a, 0xc7, 0x82, 0xc7, 0xd8, 0xfc, 0xc0, 0x10, + 0xd9, 0xf4, 0x1b, 0xfb, 0xd8, 0xf1, 0x8b, 0xab, 0xd0, 0xc0, 0x9f, 0x2e, 0xfd, 0x0f, 0xa0, 0xde, + 0xab, 0xd0, 0x90, 0x65, 0xa0, 0x8f, 0x9f, 0x4a, 0xfd, 0x0f, 0xab, 0x8b, 0x90, 0x00, 0xb9, 0xa9, + 0xc1, 0xf3, 0xae, 0xdf, 0xf8, 0xf4, 0x1c, 0x43, 0xd8, 0xf1, 0xba, 0xb1, 0xb6, 0x89, 0xab, 0xc1, + 0xb2, 0xaf, 0xd0, 0x8b, 0x9f, 0x3e, 0xfd, 0x0f, 0x5a, 0xfd, 0x0f, 0x9f, 0xfc, 0xc0, 0x00, 0xd9, + 0xf1, 0x8f, 0xa2, 0xc6, 0xd8, 0xfc, 0xc0, 0x04, 0xd9, 0x8f, 0xa2, 0xc7, 0x84, 0xab, 0xd0, 0xc0, + 0xaf, 0x8a, 0x9b, 0x1e, 0xfd, 0x0f, 0x36, 0xfd, 0x0f, 0xa4, 0x8f, 0x30, 0xaa, 0x9a, 0x40, 0xd8, + 0x9f, 0xfc, 0xc0, 0x08, 0xd9, 0x8f, 0xa2, 0xd0, 0xc6, 0x84, 0xab, 0xd0, 0xc2, 0xaf, 0x8a, 0x9b, + 0x1e, 0xfd, 0x0f, 0x56, 0xfd, 0x0f, 0xa4, 0x8f, 0x34, 0xaa, 0x9a, 0x40, 0x84, 0xab, 0xd0, 0xc4, + 0xaf, 0x8a, 0x9b, 0x3e, 0xfd, 0x0f, 0x56, 0xfd, 0x0f, 0xa4, 0xd0, 0x8f, 0x30, 0xaa, 0x9a, 0x4c, + 0xd8, 0x9f, 0xfc, 0xc0, 0x0c, 0xd9, 0x8f, 0xa2, 0xd0, 0xc7, 0x84, 0xab, 0xd0, 0xc6, 0xaf, 0x8a, + 0x9b, 0x1e, 0xfd, 0x0f, 0x76, 0xfd, 0x0f, 0xa4, 0xd0, 0x8f, 0x34, 0xaa, 0x9a, 0x40, 0x85, 0xab, + 0xd0, 0xc0, 0xaf, 0x8a, 0x9b, 0x3e, 0xfd, 0x0f, 0x76, 0xfd, 0x0f, 0xa5, 0x8f, 0x30, 0xaa, 0x9a, + 0x4c, 0x85, 0xab, 0xd0, 0xc2, 0xaf, 0x8a, 0x9b, 0x5e, 0xfd, 0x0f, 0x76, 0xfd, 0x0f, 0xa5, 0x8f, + 0x34, 0xaa, 0xd0, 0x9a, 0x50, 0xd8, 0xaf, 0xf8, 0xf4, 0x1a, 0xf1, 0xf1, 0xd8, 0x8b, 0x9c, 0xaf, + /* bank # 28 */ + 0x2a, 0xfd, 0x0f, 0x8a, 0x9f, 0xb9, 0xaf, 0x02, 0xfd, 0x0f, 0x26, 0xfd, 0x0f, 0x46, 0xfd, 0x0f, + 0x66, 0xfd, 0x0f, 0x83, 0xb5, 0x9f, 0xba, 0xa3, 0x00, 0x2c, 0x54, 0x7c, 0xb6, 0x82, 0x92, 0xa0, + 0x31, 0xd9, 0xad, 0xc3, 0xda, 0xad, 0xc5, 0xd8, 0x8d, 0xa0, 0x39, 0xda, 0x82, 0xad, 0xc7, 0xd8, + 0xf3, 0x9e, 0xfc, 0xc0, 0x04, 0xd9, 0xf4, 0x17, 0x1b, 0xd8, 0xfc, 0xc0, 0x08, 0xd9, 0xf4, 0x19, + 0x16, 0xd8, 0xf1, 0xd8, 0xf1, 0xb9, 0xb1, 0xb5, 0xa9, 0xde, 0xf8, 0x89, 0x99, 0xaf, 0x31, 0xd9, + 0xf4, 0x1c, 0x97, 0xd8, 0xf1, 0x85, 0xaf, 0x29, 0xd9, 0x84, 0xa9, 0xc2, 0xd8, 0x85, 0xaf, 0x49, + 0xd9, 0x84, 0xa9, 0xc4, 0xd8, 0x85, 0xaf, 0x69, 0xd9, 0x84, 0xa9, 0xc6, 0xd8, 0x89, 0xaf, 0x39, + 0xda, 0x8e, 0xa9, 0x50, 0xf4, 0x1c, 0x97, 0xd8, 0xf1, 0x89, 0xaa, 0x7c, 0xfd, 0x02, 0x9a, 0x68, + 0xd8, 0xf1, 0xaa, 0xfb, 0xda, 0x89, 0x99, 0xaf, 0x26, 0xfd, 0x0f, 0x8f, 0x95, 0x25, 0x89, 0x9f, + 0xa9, 0x12, 0xfd, 0x0f, 0xf4, 0x1c, 0x80, 0xd8, 0xf3, 0x9e, 0xfc, 0xc1, 0x04, 0xd9, 0xf4, 0x1b, + 0x48, 0xd8, 0xfc, 0xc1, 0x08, 0xd9, 0xf4, 0x1a, 0x63, 0xd8, 0xf1, 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, + 0xf3, 0xb8, 0xb4, 0xb0, 0x8f, 0xa8, 0xc0, 0xf9, 0xac, 0x84, 0x97, 0xf5, 0x1a, 0xf1, 0xf8, 0xf9, + 0xd1, 0xda, 0xa8, 0xde, 0xd8, 0x95, 0xfc, 0xc1, 0x03, 0xd9, 0xa8, 0xde, 0xd8, 0xbc, 0xbc, 0xf1, + 0x98, 0xfc, 0xc0, 0x1c, 0xdb, 0x95, 0xfc, 0xc0, 0x03, 0xa5, 0xde, 0xa4, 0xde, 0xd8, 0xac, 0x88, + 0x95, 0x00, 0xd1, 0xd9, 0xa5, 0xf8, 0xd8, 0xa4, 0xfc, 0x80, 0x04, 0x88, 0x95, 0xa4, 0xfc, 0x08, + 0x04, 0x20, 0xf7, 0xbc, 0xbc, 0xbd, 0xbd, 0xb5, 0xac, 0x84, 0x9f, 0xf6, 0x02, 0xf8, 0xf9, 0xd1, + /* bank # 29 */ + 0xdb, 0x84, 0x93, 0xf7, 0x6a, 0xf9, 0xd9, 0xf3, 0xbc, 0xbc, 0xa8, 0x88, 0x92, 0x18, 0xbc, 0xbc, + 0xd8, 0xbc, 0xbc, 0xb4, 0xa8, 0x88, 0x9e, 0x08, 0xf4, 0xbe, 0xbe, 0xa1, 0xd0, 0xbc, 0xbc, 0xf7, + 0xbe, 0xbe, 0xb5, 0xac, 0x84, 0x93, 0x6a, 0xf9, 0xbd, 0xbd, 0xb4, 0xd9, 0xf2, 0xac, 0x8c, 0x97, + 0x18, 0xf6, 0x84, 0x9c, 0x02, 0xf8, 0xf9, 0xdb, 0xd1, 0xf1, 0xa5, 0xdf, 0xd8, 0xf7, 0xbe, 0xbe, + 0xbd, 0xbd, 0xa7, 0x9d, 0x88, 0x7a, 0xf9, 0xd9, 0xf4, 0x1e, 0xe1, 0xd8, 0xf1, 0xbe, 0xbe, 0xac, + 0xde, 0xdf, 0xac, 0x88, 0x9f, 0xf7, 0x5a, 0x56, 0xf1, 0xbc, 0xbc, 0xbd, 0xbd, 0x95, 0xfc, 0xc0, + 0x07, 0xda, 0xf4, 0x1e, 0x7c, 0xd8, 0xf1, 0xfc, 0xc0, 0x00, 0xdb, 0x9c, 0xfc, 0xc1, 0x00, 0xf4, + 0x1e, 0xa1, 0xd8, 0xf1, 0xac, 0x95, 0xfc, 0xc0, 0x08, 0xda, 0xf4, 0x1d, 0xbe, 0xd8, 0xf1, 0x82, + 0x90, 0x79, 0x2d, 0x55, 0xf5, 0x8c, 0x9c, 0x04, 0xac, 0x2c, 0x54, 0xf1, 0xbc, 0xbc, 0xbc, 0x80, + 0x5d, 0xdb, 0x49, 0x51, 0xf4, 0xbc, 0x1d, 0x9c, 0xda, 0xbc, 0x1e, 0x78, 0xd8, 0xf5, 0x86, 0x98, + 0x38, 0xd9, 0xf1, 0x82, 0x90, 0x2d, 0xd8, 0xac, 0xd0, 0x86, 0x98, 0xf5, 0x5c, 0xd9, 0xf1, 0x82, + 0x90, 0x55, 0xd8, 0xac, 0x8c, 0x9c, 0x00, 0x00, 0xa5, 0xdf, 0xf8, 0xf4, 0x1d, 0xc9, 0xd8, 0xf1, + 0x82, 0x96, 0x2d, 0x55, 0x7d, 0x8c, 0x9c, 0x34, 0x18, 0xf1, 0xac, 0x95, 0xf5, 0x1c, 0xd9, 0xf4, + 0x1e, 0x78, 0xd8, 0xf1, 0xac, 0x83, 0x90, 0x45, 0xd9, 0xa0, 0xf8, 0xac, 0x8c, 0x9c, 0x06, 0xd2, + 0xa1, 0x91, 0x00, 0x2c, 0x81, 0xd6, 0xf0, 0xa1, 0xd0, 0x8c, 0x9c, 0x28, 0xd3, 0x87, 0xd4, 0xa7, + 0x8c, 0x20, 0xd3, 0xf1, 0xa4, 0x84, 0x90, 0x2c, 0x54, 0x7c, 0xd8, 0xac, 0x83, 0x90, 0x45, 0xd9, + /* bank # 30 */ + 0xf4, 0x1e, 0xa1, 0xd8, 0xf1, 0xac, 0x81, 0x91, 0x02, 0xfd, 0x14, 0x85, 0x66, 0xfd, 0x1d, 0x88, + 0x4e, 0xfd, 0x1b, 0x87, 0xd4, 0xfd, 0x54, 0xad, 0x8d, 0x4e, 0xf0, 0x81, 0x9c, 0xab, 0xd6, 0xfd, + 0x06, 0x8d, 0x31, 0x8c, 0x10, 0x10, 0x01, 0x01, 0x01, 0x39, 0xac, 0x8b, 0x98, 0xf5, 0x08, 0xd9, + 0xf4, 0x1e, 0x78, 0xd8, 0xf1, 0xa9, 0x82, 0x96, 0x01, 0x95, 0xfc, 0xc1, 0x00, 0xda, 0xf4, 0x1e, + 0x50, 0xdb, 0xf1, 0xac, 0x89, 0x93, 0xf5, 0x18, 0xf1, 0xa5, 0xdf, 0xf8, 0xd8, 0xf4, 0x1e, 0x7c, + 0xd8, 0xf1, 0xa4, 0x84, 0x95, 0x34, 0xfd, 0x05, 0x54, 0xfd, 0x05, 0x74, 0xfd, 0x05, 0xa9, 0x94, + 0xf5, 0x2c, 0x54, 0x7c, 0xf1, 0xac, 0x87, 0x99, 0x49, 0xdb, 0x51, 0x59, 0x84, 0xab, 0xc3, 0xc5, + 0xc7, 0x82, 0xa6, 0xc0, 0xf3, 0xaa, 0xdf, 0xf8, 0xd8, 0xf1, 0xa5, 0xdf, 0xd8, 0xf1, 0xa0, 0xde, + 0xa1, 0xde, 0xdf, 0xdf, 0xdf, 0xa7, 0xde, 0xdf, 0xa4, 0xdf, 0xdf, 0xdf, 0xa2, 0x95, 0xfc, 0xc0, + 0x01, 0xd9, 0x80, 0xc3, 0xc5, 0xc7, 0xa8, 0x83, 0xc1, 0xda, 0x86, 0xc3, 0xc5, 0xc7, 0xa8, 0x83, + 0xc3, 0xd8, 0xf1, 0x9a, 0xfc, 0xc1, 0x04, 0xd9, 0xac, 0x82, 0x96, 0x01, 0xf3, 0xaa, 0xde, 0xf8, + 0xf8, 0xf8, 0xdb, 0xf5, 0xac, 0x8c, 0x9a, 0x18, 0xf3, 0xaa, 0xf9, 0xd8, 0xac, 0x8a, 0x9a, 0x41, + 0xd1, 0xaa, 0xd0, 0xc0, 0xd9, 0xf2, 0xac, 0x85, 0x9a, 0x41, 0xdb, 0xd1, 0xbc, 0xbc, 0xbd, 0xbd, + 0xbe, 0xbe, 0xf4, 0x1e, 0xe1, 0xd8, 0xf3, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xa5, 0x85, 0x9c, + 0x10, 0xd8, 0xf1, 0xb8, 0xb0, 0xb4, 0xa7, 0x88, 0x9e, 0xf7, 0x7a, 0xf9, 0xd9, 0xf4, 0x20, 0x18, + 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xbb, 0xa2, 0xf9, 0xda, 0xbe, 0xf4, 0x20, 0x18, 0xd8, 0xf1, 0xbc, + /* bank # 31 */ + 0xbc, 0xbc, 0xb3, 0x80, 0xc6, 0xaf, 0xde, 0xd0, 0xdf, 0xbc, 0xb2, 0x84, 0xbd, 0xbd, 0xbd, 0xb7, + 0x9f, 0xa0, 0x60, 0xbc, 0xbc, 0xbc, 0xb3, 0x85, 0x90, 0xaf, 0x01, 0x9f, 0x46, 0x8f, 0xa2, 0x0e, + 0x85, 0x92, 0xaf, 0xd0, 0x29, 0x9f, 0x52, 0xa5, 0x08, 0x34, 0xa0, 0xfb, 0x86, 0x95, 0xaf, 0x29, + 0xda, 0xa6, 0xde, 0xf4, 0x1f, 0x4c, 0xd8, 0xf1, 0xa0, 0xfa, 0xf9, 0xda, 0xa6, 0xde, 0xf4, 0x1f, + 0x4c, 0xd8, 0xf1, 0xa6, 0xf8, 0x96, 0xaf, 0x19, 0xd9, 0xa3, 0xde, 0xf8, 0xd8, 0xf1, 0x85, 0x94, + 0xaf, 0x31, 0xd9, 0xa3, 0xde, 0xf8, 0xf8, 0x80, 0xa0, 0xc5, 0xd8, 0x85, 0x96, 0xaf, 0x31, 0xd9, + 0xa3, 0xde, 0xf8, 0xf8, 0xf8, 0x80, 0xa5, 0xc0, 0x86, 0xc3, 0xd8, 0xa8, 0xdf, 0xa1, 0xde, 0x85, + 0x91, 0xaf, 0x0c, 0x0d, 0xf5, 0x8f, 0x9f, 0xaf, 0x2c, 0x54, 0xf1, 0x97, 0xfc, 0xc0, 0x04, 0xdb, + 0x8f, 0xaf, 0x51, 0xa8, 0xdf, 0xf8, 0xd8, 0x98, 0xfc, 0xc0, 0x08, 0xd9, 0xf4, 0x1f, 0xb4, 0xd8, + 0xf1, 0xfc, 0xc0, 0x0c, 0xd9, 0xf4, 0x1f, 0xdd, 0xd8, 0xf1, 0x93, 0xfc, 0xc0, 0x09, 0xd9, 0xa4, + 0xde, 0xa8, 0xde, 0xf8, 0xf8, 0xd8, 0xfc, 0xc0, 0x04, 0xd9, 0x85, 0xa1, 0xc1, 0xa7, 0xde, 0xf8, + 0xd8, 0xf4, 0x1f, 0xf6, 0xd8, 0xf1, 0xa4, 0xf8, 0x82, 0x91, 0xaf, 0x31, 0xdb, 0x9f, 0x71, 0x92, + 0x41, 0xa7, 0xde, 0xd8, 0x84, 0x94, 0xaf, 0x19, 0xd9, 0xa8, 0xde, 0xf8, 0xf8, 0xf8, 0xa3, 0xdf, + 0xd8, 0x93, 0xfc, 0xc0, 0x0a, 0xd9, 0xa8, 0xde, 0xf8, 0xd8, 0xf4, 0x1f, 0xf6, 0xd8, 0xf1, 0xa4, + 0xf8, 0xa3, 0xfa, 0xf9, 0xd1, 0xdb, 0x88, 0x94, 0xaf, 0x41, 0x88, 0xa1, 0xc2, 0xd8, 0x93, 0xfc, + 0xc0, 0x0a, 0xd9, 0xa8, 0xde, 0xf8, 0xd8, 0xf1, 0x91, 0xfc, 0xc0, 0x04, 0xd9, 0xa7, 0xfa, 0xa3, + /* bank # 32 */ + 0xfa, 0xaf, 0xd0, 0xdf, 0xf8, 0xf8, 0xd8, 0xaf, 0xd0, 0xfa, 0xf9, 0xd1, 0xb0, 0xbc, 0xb4, 0xbd, + 0xb8, 0xbe, 0xda, 0xf3, 0xa5, 0x85, 0x9d, 0x08, 0xd8, 0xf1, 0xf1, 0xa7, 0xde, 0xf7, 0x84, 0x9f, + 0x6a, 0x87, 0xf1, 0xd4, 0xfd, 0x3e, 0xf9, 0xd9, 0xf4, 0x20, 0x48, 0xd8, 0xf0, 0xf7, 0xa7, 0x88, + 0x9f, 0x52, 0xf9, 0xd9, 0xf4, 0x20, 0x48, 0xd8, 0xf2, 0xbb, 0xa0, 0xf9, 0xda, 0xf4, 0x20, 0x48, + 0xd8, 0xf2, 0xb3, 0x80, 0xc4, 0xf4, 0x75, 0xdc, 0xd8, 0xf0, 0xb1, 0xb5, 0xba, 0x8a, 0x9a, 0xa7, + 0xf0, 0x2c, 0x50, 0x78, 0xf2, 0xa5, 0xde, 0xf8, 0xf8, 0xf1, 0xb5, 0xb2, 0xa7, 0x87, 0x90, 0x21, + 0xdb, 0xb6, 0xb1, 0x80, 0x97, 0x29, 0xd9, 0xf2, 0xa5, 0xf8, 0xd8, 0xbb, 0xb2, 0xb6, 0xbe, 0xa1, + 0xf8, 0xf9, 0xd1, 0xbe, 0xbe, 0xbe, 0xba, 0xda, 0xa5, 0xde, 0xd8, 0xa7, 0x82, 0x95, 0x65, 0xd1, + 0x85, 0xa2, 0xd0, 0xc1, 0xd9, 0xb5, 0xa7, 0x86, 0x93, 0x31, 0xdb, 0xd1, 0xf4, 0x20, 0x98, 0xd8, + 0xf3, 0xb8, 0xb0, 0xb4, 0xa5, 0x85, 0x9c, 0x18, 0xd8, 0xf1, 0xba, 0xb2, 0xb6, 0x81, 0x96, 0xa1, + 0xf8, 0xf9, 0xb9, 0xa6, 0xda, 0xc3, 0xc5, 0xc7, 0xd9, 0x2d, 0x4d, 0x6d, 0xd8, 0xba, 0x8a, 0xaa, + 0xf8, 0xf9, 0xb9, 0xae, 0xda, 0xc3, 0xc5, 0xc7, 0xd9, 0x2d, 0x4d, 0x6d, 0xd8, 0xba, 0x88, 0xa8, + 0xf8, 0xf9, 0xa7, 0xda, 0xc3, 0xc5, 0xc7, 0xd9, 0x2d, 0x4d, 0x6d, 0xd8, 0xf2, 0xb0, 0xb9, 0xa3, + 0xfa, 0xf9, 0xd1, 0xda, 0xb8, 0x8f, 0xa7, 0xc0, 0xf9, 0xb5, 0x87, 0x93, 0xf6, 0x0a, 0xf2, 0xb4, + 0xa4, 0x84, 0x97, 0x24, 0xa4, 0x84, 0x9e, 0x3c, 0xd8, 0xf3, 0xbe, 0xbe, 0xbb, 0xae, 0xf8, 0xf9, + 0xd1, 0xbe, 0xbe, 0xb0, 0xb4, 0xb8, 0xda, 0xa5, 0x85, 0x9e, 0x00, 0xd8, 0xf1, 0xbc, 0xbc, 0xbd, + /* bank # 33 */ + 0xbd, 0x8e, 0x9e, 0xa7, 0x59, 0xd1, 0xbc, 0xbc, 0xbd, 0xbd, 0xda, 0x85, 0x9e, 0xa5, 0x08, 0xd8, + 0xf1, 0xbc, 0xbc, 0x8e, 0xbe, 0xbe, 0xae, 0xd0, 0xc5, 0xbc, 0xbc, 0xbe, 0xbe, 0xf7, 0xb9, 0xb0, + 0xb5, 0xa6, 0x88, 0x95, 0x5a, 0xf9, 0xda, 0xf1, 0xab, 0xf8, 0xd8, 0xb8, 0xb4, 0xf3, 0x98, 0xfc, + 0xc0, 0x04, 0xda, 0xf4, 0x21, 0x86, 0xd8, 0xf2, 0xa9, 0xd0, 0xf8, 0x89, 0x9b, 0xa7, 0x51, 0xd9, + 0xa9, 0xd0, 0xde, 0xa4, 0x84, 0x9e, 0x2c, 0xd8, 0xa8, 0xfa, 0x88, 0x9a, 0xa7, 0x29, 0xd9, 0xa8, + 0xdf, 0xa4, 0x84, 0x9d, 0x34, 0xd8, 0xa8, 0xd0, 0xf8, 0x88, 0x9a, 0xa7, 0x51, 0xd9, 0xa8, 0xd0, + 0xde, 0xa4, 0x84, 0x9d, 0x2c, 0xd8, 0xa8, 0xd0, 0xfa, 0x88, 0x9a, 0xa7, 0x79, 0xd9, 0xa8, 0xd0, + 0xdf, 0xa4, 0x84, 0x9d, 0x24, 0xd8, 0xf3, 0xa9, 0xd0, 0xf8, 0x89, 0x9b, 0xa7, 0x51, 0xd9, 0xa9, + 0xd0, 0xde, 0xa4, 0x84, 0x9c, 0x2c, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, 0x52, 0xf9, 0xd9, 0xf4, 0x21, + 0xb6, 0xd8, 0xf1, 0xb9, 0xa2, 0xfa, 0xf3, 0xb8, 0xa9, 0xd0, 0xfa, 0x89, 0x9b, 0xa7, 0x79, 0xd9, + 0xa9, 0xd0, 0xdf, 0xa4, 0x84, 0x9c, 0x24, 0xd8, 0xf2, 0xa8, 0xf8, 0x88, 0x9a, 0xa7, 0x01, 0xd9, + 0xa8, 0xde, 0xa4, 0x84, 0x9d, 0x3c, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, 0x42, 0xf9, 0xd9, 0xf4, 0x21, + 0xfd, 0xd8, 0xf3, 0xa9, 0xf8, 0x89, 0x9b, 0xa7, 0x01, 0xd9, 0xa9, 0xde, 0xa4, 0x84, 0x9c, 0x3c, + 0xd8, 0xa9, 0xfa, 0x89, 0x9b, 0xa7, 0x29, 0xd9, 0xa9, 0xdf, 0xa4, 0x84, 0x9c, 0x34, 0xd8, 0xf2, + 0xa9, 0xfa, 0x89, 0x9b, 0xa7, 0x29, 0xd9, 0xa9, 0xdf, 0xa4, 0x84, 0x9e, 0x34, 0xd8, 0xa9, 0xd0, + 0xfa, 0x89, 0x9b, 0xa7, 0x79, 0xd9, 0xa9, 0xd0, 0xdf, 0xa4, 0x84, 0x9e, 0x24, 0xd8, 0xf1, 0xa7, + /* bank # 34 */ + 0xde, 0xf2, 0x84, 0xca, 0x97, 0xa4, 0x24, 0xa5, 0x94, 0xf6, 0x0a, 0xf7, 0x85, 0x02, 0xf8, 0xf9, + 0xd1, 0xd9, 0xf6, 0x9b, 0x02, 0xd8, 0xa7, 0xb1, 0x82, 0x95, 0x62, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, + 0x23, 0xf2, 0xd8, 0xf0, 0xb0, 0x85, 0xa4, 0xd0, 0xc0, 0xdd, 0xf2, 0xc0, 0xdc, 0xf6, 0xa7, 0x9f, + 0x02, 0xf9, 0xd9, 0xf3, 0xa5, 0xde, 0xda, 0xf0, 0xdd, 0xf2, 0xc8, 0xdc, 0xd8, 0x85, 0x95, 0xa5, + 0x00, 0xd9, 0x86, 0xf0, 0xdd, 0xf2, 0xca, 0xcc, 0xce, 0xdc, 0xd8, 0x85, 0x00, 0xd9, 0x80, 0xf0, + 0xdd, 0xf2, 0xcc, 0xc6, 0xce, 0x85, 0xca, 0xcc, 0xce, 0xdc, 0xd8, 0x85, 0x00, 0xd9, 0xb1, 0x89, + 0xf0, 0xdd, 0xf2, 0xc2, 0xca, 0xc4, 0xdc, 0xd8, 0xb0, 0x85, 0x00, 0xd9, 0x81, 0xf0, 0xdd, 0xf2, + 0xc6, 0xce, 0x82, 0xc0, 0xc8, 0xdc, 0xd8, 0x85, 0x00, 0xb1, 0xd9, 0x86, 0xf0, 0xdd, 0xf1, 0xc2, + 0xc4, 0xc6, 0xdc, 0xd8, 0xb0, 0xf2, 0x85, 0x00, 0xd9, 0xb2, 0x87, 0xf0, 0xdd, 0xf1, 0xc2, 0xc4, + 0xc6, 0xf2, 0xbc, 0xb0, 0x81, 0xc0, 0xdc, 0xbc, 0xbc, 0xbc, 0xd8, 0xb0, 0x85, 0x00, 0xb1, 0xd9, + 0x8f, 0xf0, 0xdd, 0xf2, 0xc2, 0xc4, 0xc6, 0xdc, 0xd8, 0xb0, 0x85, 0x00, 0xd9, 0xb1, 0x8e, 0xf0, + 0xdd, 0xf1, 0xc2, 0xc4, 0xc6, 0xf2, 0xbc, 0xb0, 0x81, 0xc0, 0xdc, 0xbc, 0xbc, 0xbc, 0xd8, 0xb0, + 0x85, 0x00, 0xd9, 0x82, 0xf0, 0xdd, 0xf2, 0xc2, 0xca, 0xc4, 0xdc, 0xd8, 0x85, 0x00, 0xd8, 0xf2, + 0x85, 0x00, 0xd9, 0xb1, 0x8a, 0xf0, 0xdd, 0xf1, 0xc2, 0xc4, 0xc6, 0xdc, 0xd8, 0xb0, 0xf2, 0x85, + 0x00, 0xd9, 0xb1, 0xf0, 0xdd, 0xf1, 0x82, 0xc4, 0xdc, 0xd8, 0xb0, 0xf3, 0xa5, 0xf8, 0xf9, 0xd1, + 0xd9, 0xf4, 0x23, 0x74, 0xd8, 0xf3, 0x85, 0x95, 0xa5, 0x00, 0x00, 0xd9, 0xbe, 0xf2, 0xba, 0xae, + /* bank # 35 */ + 0xde, 0xbe, 0xbe, 0xbe, 0xbc, 0xb2, 0x81, 0xf0, 0xdd, 0xf3, 0xc8, 0xdc, 0xbc, 0xbc, 0xbc, 0xd8, + 0xb0, 0xb8, 0x85, 0xa5, 0x00, 0xd9, 0xf2, 0xbe, 0xbe, 0xaa, 0xde, 0xbe, 0xbe, 0xbc, 0xbc, 0x8a, + 0xf0, 0xdd, 0xf3, 0xc0, 0xdc, 0xbc, 0xbc, 0xd8, 0x85, 0xa5, 0x00, 0xd9, 0xb9, 0xf2, 0xa3, 0xd0, + 0xde, 0xb2, 0x85, 0xf0, 0xdd, 0xf3, 0xc8, 0xdc, 0xd8, 0xb0, 0x85, 0xb8, 0xa5, 0x00, 0xd9, 0xb3, + 0x8a, 0xf0, 0xdd, 0xf3, 0xc0, 0xdc, 0xd8, 0xb0, 0x85, 0x00, 0xd9, 0x8f, 0xf0, 0xdd, 0xf3, 0xc4, + 0xdc, 0xd8, 0x85, 0x00, 0x00, 0x00, 0xd9, 0xbc, 0xbc, 0xb3, 0x8e, 0xf0, 0xdd, 0xf3, 0xc0, 0xf1, + 0xc2, 0xdc, 0xbc, 0xbc, 0xd8, 0xf3, 0xb0, 0x85, 0x00, 0xd9, 0xbc, 0xbc, 0x8e, 0xf0, 0xdd, 0xf3, + 0xc4, 0xdc, 0xbc, 0xbc, 0xd8, 0xf3, 0xb0, 0x8e, 0xf4, 0xb8, 0xa7, 0xd0, 0xc0, 0xd8, 0x87, 0xf3, + 0xb9, 0xa2, 0xc6, 0xa6, 0xc4, 0xf7, 0xb5, 0x8e, 0x96, 0x06, 0xf8, 0xf9, 0xd1, 0xda, 0xf4, 0x23, + 0x7d, 0xd8, 0xf3, 0x8e, 0xc0, 0xf9, 0xb1, 0x86, 0x96, 0xf7, 0x0a, 0xdf, 0xf3, 0x30, 0xfd, 0x08, + 0xa2, 0x82, 0x10, 0xf0, 0xdd, 0xf3, 0x82, 0xc0, 0xdc, 0xf2, 0xb9, 0xa3, 0xdf, 0xf4, 0xb1, 0x8c, + 0xf3, 0xaf, 0xc1, 0xc3, 0xaf, 0x8f, 0xb4, 0x9d, 0x3e, 0xfd, 0x1e, 0xb5, 0x9f, 0x30, 0xa6, 0x39, + 0xd9, 0xf4, 0x23, 0xec, 0xd8, 0xf7, 0xb8, 0xb0, 0xb4, 0xa7, 0x84, 0x9d, 0x1a, 0xf9, 0xd9, 0xf4, + 0x23, 0xdf, 0xd8, 0xf1, 0xb9, 0xb1, 0xb5, 0xa6, 0x83, 0x9b, 0x61, 0xd9, 0xf4, 0x23, 0xf2, 0xd8, + 0xf6, 0xb8, 0xb0, 0xb4, 0xa7, 0x84, 0x94, 0x5a, 0xf8, 0xf9, 0xd1, 0xda, 0xf0, 0xe2, 0xf1, 0xb9, + 0xab, 0xde, 0xd8, 0xf2, 0xb1, 0x86, 0xb9, 0xaf, 0xc3, 0xc5, 0xc7, 0xb8, 0xb0, 0xb4, 0xa7, 0x88, + /* bank # 36 */ + 0x9c, 0xf7, 0x6a, 0xf9, 0xd9, 0xff, 0xd8, 0x72, 0xb9, 0xab, 0xf1, 0xdf, 0xf7, 0x62, 0xf3, 0xf8, + 0xf9, 0xd1, 0xda, 0xf1, 0xde, 0xf8, 0xd8, 0xf7, 0xbb, 0xaf, 0x7a, 0x9d, 0x66, 0x9e, 0x76, 0x9f, + 0x76, 0xf1, 0xa1, 0xdf, 0xba, 0xa6, 0xd0, 0xde, 0xbb, 0xf3, 0xa0, 0xf9, 0xda, 0xff, 0xd8, 0xb3, + 0x80, 0xc4, 0xaf, 0xd0, 0xfa, 0xf9, 0xd1, 0xda, 0xbc, 0xbc, 0xbc, 0xf4, 0x25, 0xba, 0xd8, 0xf1, + 0xb8, 0xbe, 0xbe, 0xae, 0xd0, 0xde, 0xb0, 0x84, 0xba, 0xbe, 0xa7, 0xc1, 0xf7, 0x88, 0xb4, 0x9d, + 0x6e, 0xf9, 0xb2, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xda, 0xf4, 0x24, 0x8f, 0xd8, 0xf1, 0xb8, + 0xbe, 0xbe, 0xbe, 0xae, 0xd0, 0x91, 0xfc, 0xc0, 0x00, 0xdb, 0xb6, 0x95, 0xfc, 0xc1, 0x04, 0xd9, + 0xf8, 0xf8, 0xf8, 0xf8, 0xd8, 0xb4, 0x91, 0xfc, 0xc0, 0x04, 0xdb, 0xb6, 0x95, 0xfc, 0xc1, 0x00, + 0xd9, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xd8, 0xba, 0xbe, 0xf4, 0x24, 0xf6, 0xd8, + 0xf1, 0x91, 0xfc, 0xc0, 0x00, 0xdb, 0xb6, 0x95, 0xfc, 0xc1, 0x04, 0xf5, 0x87, 0x95, 0xa7, 0x3a, + 0xf1, 0xf9, 0xd9, 0xaf, 0xde, 0x8f, 0xbe, 0xbe, 0xa1, 0xf4, 0xc1, 0xf1, 0xa2, 0xf4, 0xc1, 0xf1, + 0xbe, 0xbe, 0xd8, 0xb4, 0x91, 0xfc, 0xc0, 0x04, 0xdb, 0xb6, 0x95, 0xfc, 0xc1, 0x00, 0xd9, 0xaf, + 0xde, 0xf8, 0xfd, 0x07, 0x8f, 0x95, 0x10, 0xdf, 0xf8, 0xf8, 0xf8, 0xa7, 0xde, 0xf8, 0xfd, 0x07, + 0xdf, 0xf8, 0xfd, 0x06, 0xdf, 0xf8, 0xfd, 0x04, 0x8f, 0x97, 0xaf, 0xd0, 0xde, 0x40, 0x48, 0x50, + 0xdf, 0xf8, 0x60, 0x8f, 0xbe, 0xbe, 0xa0, 0xd0, 0xf4, 0xc1, 0xf1, 0xa1, 0xf4, 0xc2, 0xc5, 0xf1, + 0xa2, 0xf4, 0xc7, 0xf1, 0xbe, 0xbe, 0xd8, 0xf1, 0xb0, 0x81, 0xa5, 0xc1, 0xbc, 0x84, 0xb8, 0xbe, + /* bank # 37 */ + 0xbe, 0xa9, 0xc1, 0xf7, 0x88, 0xb4, 0xbd, 0x9d, 0x6e, 0xf9, 0xbc, 0xbd, 0xda, 0xf4, 0x25, 0x43, + 0xd8, 0xf1, 0xa9, 0xde, 0xf8, 0xfd, 0x04, 0xdf, 0xf8, 0xfd, 0x05, 0xbc, 0x8e, 0xbe, 0xae, 0xd0, + 0x9a, 0xfc, 0xc0, 0x00, 0xdb, 0x9b, 0xfc, 0xc0, 0x04, 0xd9, 0x99, 0x40, 0xd8, 0x9a, 0xfc, 0xc0, + 0x04, 0xdb, 0x9b, 0xfc, 0xc0, 0x00, 0xd9, 0x99, 0x48, 0xd8, 0xbc, 0xbc, 0xbc, 0xbe, 0xbe, 0xbe, + 0xf4, 0x25, 0xad, 0xd8, 0xf1, 0x9a, 0xfc, 0xc0, 0x00, 0xdb, 0x9b, 0xfc, 0xc0, 0x04, 0xf5, 0x89, + 0xa9, 0x32, 0xf9, 0xd9, 0xf1, 0xde, 0xf8, 0xfd, 0x02, 0xdf, 0xf8, 0xfd, 0x07, 0xdf, 0xf8, 0xfd, + 0x07, 0xf8, 0xdf, 0x89, 0xba, 0xa0, 0xf4, 0xc0, 0xf1, 0x8b, 0xa1, 0xd0, 0xf4, 0xc3, 0xf1, 0x89, + 0xa2, 0xf4, 0xc2, 0xc5, 0xc7, 0xf1, 0xa3, 0xf4, 0xc7, 0xf1, 0xb8, 0xd8, 0x9a, 0xfc, 0xc0, 0x04, + 0xdb, 0x9b, 0xfc, 0xc0, 0x00, 0xd9, 0xa9, 0xde, 0xf8, 0xfd, 0x02, 0xdf, 0xf8, 0xfd, 0x07, 0xdf, + 0xf8, 0xfd, 0x07, 0xf8, 0xdf, 0xf8, 0xfd, 0x04, 0xf9, 0x89, 0xba, 0xa0, 0xf4, 0xc0, 0xf1, 0x8b, + 0xa1, 0xd0, 0xf4, 0xc3, 0xf1, 0x89, 0xa2, 0xf4, 0xc2, 0xc5, 0xc7, 0xf1, 0xb8, 0xd8, 0xf1, 0x8a, + 0xab, 0xc0, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbe, 0xbe, 0xbe, 0xd8, 0xf1, 0xb2, 0x80, 0xba, 0xa7, + 0xc4, 0xbc, 0xb2, 0x8b, 0xf4, 0x75, 0x75, 0x8f, 0xb6, 0x9c, 0xf4, 0x75, 0x81, 0xaf, 0xf4, 0x75, + 0x87, 0x8b, 0xf4, 0x75, 0x75, 0x8e, 0xb6, 0x9d, 0xf4, 0x75, 0x81, 0xae, 0xf4, 0x75, 0x87, 0xb3, + 0x81, 0xf4, 0x75, 0x75, 0x85, 0x94, 0xf4, 0x75, 0x81, 0xbb, 0xa5, 0xf4, 0x75, 0x87, 0x80, 0xba, + 0xf4, 0x75, 0x75, 0xb3, 0x8e, 0x9b, 0xf4, 0x75, 0x81, 0xbb, 0xae, 0xf4, 0x75, 0x87, 0xb3, 0x83, + /* bank # 38 */ + 0xa3, 0xf4, 0x75, 0x93, 0xf1, 0xb2, 0x8f, 0xb6, 0x9f, 0xbe, 0xbe, 0xb9, 0xaf, 0x7a, 0x8e, 0x9e, + 0x7e, 0xf5, 0xb3, 0x85, 0xb7, 0x95, 0x7c, 0x8e, 0x9e, 0x7c, 0xf1, 0xbc, 0xbc, 0xbd, 0xbd, 0xb1, + 0xb5, 0x8f, 0x9f, 0xaf, 0xd0, 0x58, 0x82, 0xaf, 0x01, 0x2d, 0x55, 0x86, 0xaf, 0x42, 0x4e, 0x76, + 0x82, 0xa2, 0x00, 0x2c, 0x54, 0x84, 0xbd, 0xb6, 0x90, 0xaf, 0x51, 0xbd, 0xbd, 0xbd, 0xb5, 0x9f, + 0x06, 0xa4, 0xd0, 0x48, 0x8f, 0xaf, 0xd0, 0x0a, 0x84, 0x74, 0xa4, 0xd0, 0x3e, 0x80, 0x93, 0xaf, + 0x39, 0xd1, 0xab, 0xd9, 0xfa, 0xda, 0xdf, 0xd8, 0xba, 0xad, 0xfa, 0x83, 0x9b, 0xa7, 0x69, 0xdb, + 0xb2, 0x8d, 0xb6, 0x9d, 0x69, 0xf4, 0x26, 0x6d, 0xd8, 0xf1, 0xad, 0xde, 0xdf, 0xd8, 0xf0, 0xbc, + 0xb2, 0x81, 0xbd, 0xb6, 0x91, 0xbb, 0xa6, 0x3c, 0x11, 0x0c, 0x58, 0x2c, 0x50, 0xf1, 0xbc, 0xbc, + 0xbc, 0xb3, 0x86, 0xbd, 0xbd, 0xbd, 0xb7, 0x96, 0xa6, 0x2c, 0x54, 0x7c, 0x9b, 0x71, 0x97, 0xa5, + 0xd0, 0x2a, 0xf0, 0x50, 0x78, 0xf1, 0xd8, 0xb8, 0xac, 0xde, 0xf8, 0xf5, 0xb0, 0x8c, 0xb7, 0x93, + 0x06, 0xf1, 0xf9, 0xaf, 0xda, 0xf8, 0xd9, 0xde, 0xd8, 0xb3, 0xb6, 0xba, 0x86, 0xa7, 0xc2, 0xf4, + 0x75, 0x9b, 0x93, 0xf0, 0x71, 0x71, 0x60, 0x84, 0x92, 0xf4, 0x75, 0x81, 0xf1, 0xa4, 0xf4, 0x75, + 0x87, 0x83, 0xa3, 0xf4, 0x75, 0x93, 0xb3, 0x86, 0xa7, 0xc4, 0xf4, 0x75, 0x9b, 0x95, 0xf0, 0x71, + 0x71, 0x60, 0x86, 0x92, 0xf4, 0x75, 0x81, 0xa6, 0xf4, 0x75, 0x87, 0x85, 0xa5, 0xf4, 0x75, 0x93, + 0xb3, 0x86, 0xa7, 0xc6, 0xf4, 0x75, 0x9b, 0x9f, 0xf0, 0x71, 0x71, 0x60, 0x88, 0x92, 0xf4, 0x75, + 0x81, 0xa8, 0xf4, 0x75, 0x87, 0x8f, 0xaf, 0xf4, 0x75, 0x93, 0xf5, 0xb2, 0x84, 0x94, 0xb9, 0xaf, + /* bank # 39 */ + 0x7c, 0x86, 0x96, 0x7c, 0x88, 0x98, 0x7c, 0xf1, 0xb1, 0x8f, 0xb5, 0x9f, 0xa5, 0x30, 0x85, 0x18, + 0xf0, 0x9a, 0x3c, 0x99, 0x18, 0xf1, 0xbc, 0xbc, 0xb2, 0x84, 0xb9, 0xaf, 0xc3, 0xc5, 0xc7, 0xba, + 0xb6, 0xbc, 0xbc, 0xa7, 0x8b, 0xb5, 0x9f, 0x2d, 0x55, 0x7d, 0xf5, 0xa7, 0x87, 0xb6, 0x97, 0x2c, + 0x54, 0x7c, 0xf0, 0xac, 0x81, 0x9c, 0x0c, 0x97, 0x28, 0x9c, 0x14, 0x97, 0x30, 0x9c, 0x1c, 0x97, + 0x38, 0xf1, 0xb1, 0x8f, 0xab, 0xc3, 0xc5, 0xc7, 0xa7, 0xb2, 0x81, 0x9c, 0x59, 0xdb, 0x51, 0xaa, + 0xde, 0xf4, 0x27, 0x6a, 0xd8, 0xf1, 0xac, 0xb1, 0x8e, 0x9c, 0x48, 0xfd, 0x02, 0xb2, 0x8b, 0x02, + 0xaa, 0xde, 0xa7, 0x8c, 0x11, 0xdb, 0x19, 0xda, 0xaa, 0xf8, 0xd8, 0xf1, 0xb5, 0xbd, 0xbd, 0x9b, + 0xfc, 0xc1, 0x03, 0xbd, 0xbd, 0xd9, 0xf4, 0x28, 0xea, 0xd8, 0xf1, 0xb2, 0xbc, 0xbc, 0x84, 0xb8, + 0xbe, 0xae, 0xc3, 0xc5, 0xc7, 0xb0, 0xbc, 0xbc, 0xbc, 0xb4, 0xbd, 0xf0, 0x8a, 0x9e, 0xaf, 0x6c, + 0x99, 0x61, 0x8a, 0x19, 0x9e, 0x74, 0x99, 0x69, 0x8a, 0x39, 0x9e, 0x7c, 0x99, 0x71, 0x8a, 0x59, + 0xf1, 0x8f, 0x9f, 0xaa, 0x28, 0xfd, 0x01, 0x54, 0xfd, 0x01, 0x7c, 0xfd, 0x01, 0x8e, 0xa9, 0xc2, + 0xc5, 0xc7, 0xf0, 0x8a, 0x9a, 0xa7, 0x04, 0x28, 0x50, 0xf1, 0x87, 0x97, 0xaf, 0x09, 0x8f, 0xb5, + 0xbd, 0xbd, 0xbd, 0x9b, 0x1e, 0xb4, 0xbd, 0x97, 0xa7, 0x20, 0x8b, 0xba, 0xa7, 0xc1, 0xc3, 0xc5, + 0xbd, 0xb6, 0x90, 0xfc, 0xc2, 0x00, 0xbd, 0xbd, 0xbd, 0xd9, 0xf4, 0x28, 0x77, 0xd8, 0xf1, 0xb2, + 0x86, 0xb6, 0x97, 0xa7, 0x4a, 0x99, 0xf4, 0x75, 0xa1, 0x9a, 0xf4, 0x75, 0x81, 0x8a, 0xaa, 0xf4, + 0x75, 0x93, 0xf1, 0x86, 0x97, 0xa7, 0x52, 0x9b, 0xf4, 0x75, 0xa1, 0x9c, 0xf4, 0x75, 0x81, 0x8c, + /* bank # 40 */ + 0xac, 0xf4, 0x75, 0x93, 0xf1, 0x86, 0x97, 0xa7, 0x5a, 0x9d, 0xf4, 0x75, 0xa1, 0x9e, 0xf4, 0x75, + 0x81, 0x8e, 0xae, 0xf4, 0x75, 0x93, 0xf1, 0x89, 0xa9, 0xc2, 0xc5, 0xc7, 0x87, 0xc3, 0x8b, 0xab, + 0xc2, 0xc5, 0xc7, 0x87, 0xc5, 0x8d, 0xad, 0xc2, 0xc5, 0xc7, 0x87, 0xc7, 0xb8, 0xae, 0xde, 0x8a, + 0xb4, 0x9e, 0x64, 0xfd, 0x01, 0x8c, 0x64, 0xfd, 0x01, 0x8e, 0x64, 0xfd, 0x01, 0xb0, 0xf0, 0x8d, + 0x9e, 0xaf, 0x6c, 0x9c, 0x61, 0x8d, 0x19, 0x9e, 0x74, 0x9c, 0x69, 0x8d, 0x39, 0x9e, 0x7c, 0x9c, + 0x71, 0x8d, 0x59, 0xf1, 0x8f, 0x9f, 0xad, 0x28, 0xfd, 0x01, 0x54, 0xfd, 0x01, 0x7c, 0xfd, 0x01, + 0x8e, 0xac, 0xc2, 0xc5, 0xc7, 0xf0, 0x8d, 0x9d, 0xa8, 0x04, 0x28, 0x50, 0xf1, 0x88, 0x98, 0xaf, + 0x09, 0x8f, 0x9b, 0x1e, 0x98, 0xa8, 0x20, 0xd8, 0xf1, 0xb8, 0xb1, 0xb4, 0xbc, 0xbc, 0xbc, 0x84, + 0xaf, 0xc7, 0x87, 0xc1, 0xb3, 0x83, 0xc1, 0xbc, 0xb0, 0x8f, 0x9f, 0xaf, 0x49, 0xda, 0xf4, 0x28, + 0xa7, 0xd8, 0xf5, 0x91, 0x7a, 0xf1, 0x9f, 0xfc, 0xc0, 0x03, 0xdb, 0x90, 0xfc, 0xc0, 0x00, 0xd9, + 0xa1, 0xde, 0xf8, 0xd8, 0xf4, 0x28, 0xb7, 0xd8, 0xf5, 0x91, 0x72, 0xf1, 0x9f, 0xfc, 0xc0, 0x03, + 0xd9, 0xa1, 0xde, 0xdf, 0xa0, 0xde, 0xdf, 0xd8, 0xf1, 0xa1, 0xf8, 0xf9, 0xd1, 0xa0, 0xda, 0xf8, + 0xd9, 0xfa, 0xd8, 0x80, 0x90, 0xaf, 0x11, 0xdb, 0xa1, 0xde, 0x91, 0xfc, 0xc1, 0x04, 0xd9, 0xa1, + 0xf8, 0xdf, 0xa0, 0xde, 0xd8, 0x80, 0x90, 0xaf, 0x39, 0xd9, 0xa0, 0xde, 0xdf, 0xa1, 0xdf, 0xd8, + 0xf1, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbe, 0xbe, 0xbe, 0xd8, 0xf1, 0xb1, 0xb5, 0xb9, 0xa6, + 0xf8, 0x8a, 0xbb, 0xa4, 0xc3, 0xa0, 0xc5, 0xb9, 0x86, 0x96, 0xaf, 0x21, 0xd9, 0xf4, 0x30, 0x31, + /* bank # 41 */ + 0xd8, 0xf1, 0xa6, 0xde, 0xa1, 0xde, 0xdf, 0xdf, 0xa0, 0xde, 0xdf, 0xdf, 0xdf, 0xab, 0xde, 0xac, + 0xde, 0xb3, 0x8c, 0xbb, 0xa4, 0xd0, 0xc4, 0xa0, 0xd0, 0xc6, 0xb8, 0xbe, 0xbe, 0xbe, 0x83, 0xa9, + 0xc1, 0xf2, 0xbc, 0xbc, 0x82, 0xc3, 0x81, 0xc5, 0xf8, 0xf1, 0xb0, 0xbc, 0xbd, 0xbd, 0x9b, 0xfc, + 0xc1, 0x03, 0xb4, 0xbd, 0xd9, 0xf4, 0x29, 0x84, 0xd8, 0xf1, 0xaa, 0xde, 0x99, 0xfc, 0xc1, 0x00, + 0xd9, 0xaa, 0xfa, 0xdb, 0x8a, 0x9a, 0xa9, 0x39, 0xaa, 0xde, 0xf8, 0xd8, 0xf5, 0xa2, 0x89, 0x92, + 0x3a, 0xf1, 0x92, 0xfc, 0xc0, 0x03, 0xda, 0xdf, 0xd9, 0xfa, 0xa2, 0x82, 0xdb, 0x31, 0xdf, 0xaa, + 0xde, 0xf8, 0xd8, 0x99, 0xfc, 0xc1, 0x03, 0xd9, 0xaa, 0xdf, 0xd8, 0xf2, 0x89, 0x99, 0xa9, 0x71, + 0xdb, 0xde, 0x41, 0xf1, 0xaa, 0xde, 0xf8, 0xd8, 0x9a, 0xfc, 0xc0, 0x04, 0xdb, 0xa8, 0xde, 0x98, + 0xfc, 0xc1, 0x00, 0xf8, 0xd8, 0xf1, 0xb1, 0xbc, 0xb5, 0xbd, 0xb9, 0xbe, 0x87, 0x94, 0xaf, 0x19, + 0xd9, 0x83, 0xa1, 0xc6, 0xf4, 0x2c, 0x7a, 0xd8, 0xf1, 0x82, 0x9f, 0xaf, 0xdf, 0x28, 0xfd, 0x03, + 0xdf, 0x30, 0xfd, 0x04, 0x8f, 0x9f, 0x34, 0x82, 0x38, 0x1d, 0xa9, 0xde, 0xd9, 0xf8, 0xda, 0xf4, + 0x2a, 0xeb, 0xd8, 0xf1, 0x82, 0x97, 0xaf, 0x51, 0xd9, 0x83, 0xa0, 0xc7, 0x83, 0xa7, 0xd0, 0xc2, + 0xf4, 0x2a, 0x1c, 0xd8, 0xf1, 0x82, 0x92, 0xaf, 0x59, 0xda, 0xf4, 0x2a, 0x1c, 0xd8, 0xf5, 0xb3, + 0x83, 0xb7, 0x99, 0x1a, 0xf1, 0xf8, 0xf9, 0xd1, 0xda, 0xb1, 0xb5, 0xf4, 0x2a, 0x1c, 0xd8, 0xf5, + 0x3a, 0xf1, 0xf8, 0xf9, 0xd1, 0xda, 0xb1, 0xb5, 0xf4, 0x2a, 0x1c, 0xd8, 0xf1, 0xb0, 0xbc, 0xbc, + 0xbc, 0x88, 0xaf, 0xc1, 0xf2, 0x89, 0xc5, 0xc7, 0xf9, 0xf9, 0xb1, 0xbc, 0xb5, 0xb9, 0xf2, 0x8f, + /* bank # 42 */ + 0x9f, 0xaf, 0x71, 0xd9, 0xf1, 0x83, 0xa0, 0xc6, 0xb3, 0x8c, 0xbb, 0xa4, 0xd0, 0xc4, 0xa0, 0xd0, + 0xc6, 0xb1, 0xb9, 0xd8, 0xf1, 0x83, 0xac, 0xc6, 0x83, 0xa7, 0xd0, 0xc4, 0xd8, 0xf1, 0xbc, 0xbc, + 0x81, 0xaf, 0xc3, 0xf3, 0x8b, 0xc3, 0xf2, 0xb3, 0x82, 0xc2, 0x81, 0xc5, 0xf9, 0xf1, 0xb1, 0xbc, + 0xbc, 0x83, 0x9f, 0xaf, 0x09, 0xdb, 0x8f, 0x9e, 0x31, 0x83, 0xa1, 0xc7, 0xa0, 0xdf, 0xd0, 0xde, + 0x9f, 0xfc, 0xc2, 0x01, 0xd9, 0xf2, 0xaf, 0xde, 0xf8, 0xf8, 0xf8, 0x8f, 0xdb, 0x41, 0xd9, 0xf1, + 0x8e, 0xb7, 0x91, 0xbb, 0xa2, 0xd0, 0x5c, 0xfd, 0x3f, 0xb5, 0xb9, 0xd8, 0x8f, 0x93, 0xaf, 0x21, + 0xdb, 0x83, 0xa0, 0xc7, 0xd0, 0xde, 0xa1, 0xdf, 0x9f, 0xfc, 0xc2, 0x01, 0xd9, 0xf2, 0xaf, 0xde, + 0xf8, 0xf8, 0xf8, 0x8f, 0xdb, 0x41, 0xd9, 0xf1, 0x8e, 0xb7, 0x91, 0xbb, 0xa2, 0xd0, 0x5c, 0xfd, + 0x3f, 0xb5, 0xb9, 0xd8, 0xf1, 0x9f, 0xfc, 0xc2, 0x01, 0xd9, 0xf4, 0x2a, 0xba, 0xd8, 0xf3, 0xbc, + 0xbc, 0xaf, 0xd0, 0xb1, 0x8c, 0xc4, 0xf1, 0xb0, 0xbc, 0x8a, 0xaf, 0xc5, 0xb1, 0xbc, 0x80, 0x93, + 0xaf, 0x39, 0xd1, 0xd9, 0xf3, 0xd0, 0xf8, 0xf9, 0xdb, 0xd1, 0xf1, 0x9f, 0xfc, 0xc1, 0x04, 0xf2, + 0x8f, 0x9f, 0xaf, 0x59, 0xf1, 0xa0, 0xdf, 0x83, 0xd0, 0xc6, 0xd8, 0xf1, 0xa1, 0xd0, 0xde, 0x83, + 0x90, 0xaf, 0x69, 0xdb, 0x91, 0x69, 0xf4, 0x2a, 0xd4, 0xd8, 0xf2, 0x8f, 0x9f, 0x71, 0xd9, 0xf1, + 0x83, 0xa1, 0xd0, 0xc6, 0xd8, 0xf1, 0x80, 0x93, 0xaf, 0x19, 0xd1, 0xd9, 0xf4, 0x2b, 0x5a, 0xd8, + 0xf1, 0x79, 0xd1, 0xd9, 0xf4, 0x2b, 0x5a, 0xd8, 0xf4, 0x2c, 0xbb, 0xd8, 0xf1, 0x82, 0x9d, 0xaf, + 0x31, 0xda, 0xf4, 0x2b, 0x1c, 0xd8, 0xf1, 0x83, 0xa0, 0xd0, 0xc7, 0xb6, 0x9d, 0xfc, 0xc2, 0x04, + /* bank # 43 */ + 0xd9, 0xba, 0xad, 0xde, 0xf8, 0xd8, 0xb3, 0x8a, 0xb7, 0x92, 0xbb, 0xaf, 0x19, 0xb1, 0x88, 0xa4, + 0xd9, 0xc5, 0xa0, 0xc7, 0xda, 0xc1, 0xa0, 0xc3, 0xd8, 0xf4, 0x2b, 0x5a, 0xd8, 0xf1, 0xa1, 0xf8, + 0xf9, 0xd1, 0xda, 0xf4, 0x2b, 0x5a, 0xd8, 0xf1, 0xba, 0xad, 0xf8, 0xf9, 0xd1, 0xd9, 0x83, 0xb9, + 0xa0, 0xc6, 0xab, 0xc6, 0xb3, 0x8d, 0xbb, 0xa4, 0xd0, 0xc4, 0xa0, 0xd0, 0xc6, 0xf4, 0x2b, 0x5a, + 0xd8, 0xf1, 0x83, 0xb9, 0xa0, 0xd0, 0xc7, 0xb3, 0x8a, 0xb7, 0x92, 0xbb, 0xaf, 0x19, 0xb1, 0xa4, + 0xd9, 0x89, 0xc3, 0xa0, 0xc5, 0xda, 0x88, 0xc1, 0xa0, 0xc3, 0xd8, 0xf1, 0xb1, 0x85, 0xba, 0xbe, + 0xaf, 0xc2, 0x84, 0xc7, 0x82, 0xc1, 0xc3, 0xb2, 0xbc, 0xb6, 0xbd, 0xa7, 0xdf, 0xdf, 0x8f, 0x92, + 0xa7, 0x01, 0xd9, 0xf4, 0x2b, 0x9c, 0xd8, 0xf1, 0x09, 0xd9, 0xf4, 0x2b, 0x83, 0xd8, 0xf1, 0xfa, + 0xf4, 0x2b, 0xcb, 0xd8, 0xf1, 0x51, 0xd9, 0xf4, 0x2b, 0x90, 0xd8, 0xf1, 0xfa, 0xf4, 0x2b, 0xcb, + 0xd8, 0xf1, 0x19, 0xd9, 0xd0, 0xf8, 0xda, 0xfa, 0xd8, 0xf4, 0x2b, 0xcb, 0xd8, 0xf1, 0x93, 0x21, + 0xd9, 0xf4, 0x2b, 0xb0, 0xd8, 0xf1, 0x09, 0xd9, 0xd0, 0xf8, 0xda, 0xfa, 0xd8, 0xf4, 0x2b, 0xcb, + 0xd8, 0xf1, 0x71, 0xd9, 0xd0, 0xf8, 0xf4, 0x2b, 0xcb, 0xd8, 0xf1, 0x59, 0xd9, 0xd0, 0xf8, 0xf4, + 0x2b, 0xcb, 0xd8, 0xf1, 0x94, 0x01, 0xd9, 0xd0, 0xf8, 0xda, 0xfa, 0xd8, 0xf1, 0xb0, 0xbc, 0xbc, + 0x88, 0xa7, 0xc0, 0xb1, 0xbc, 0x89, 0xd0, 0xc1, 0x82, 0xaf, 0xd0, 0xc5, 0xb2, 0xbc, 0xb5, 0xbd, + 0x9b, 0xfc, 0xc1, 0x00, 0xb6, 0xbd, 0xbd, 0xbd, 0xdb, 0x97, 0xfc, 0xc3, 0x04, 0xfc, 0xc0, 0x00, + 0xfc, 0xc2, 0x04, 0xd9, 0xa7, 0xdf, 0xf8, 0xdf, 0xd8, 0xf1, 0x8f, 0x94, 0xa7, 0x71, 0xd9, 0xf4, + /* bank # 44 */ + 0x2c, 0x14, 0xd8, 0xf1, 0x95, 0x41, 0xd9, 0xf4, 0x2c, 0x14, 0xd8, 0xf1, 0x94, 0x09, 0xdb, 0x39, + 0xd9, 0xdf, 0xdf, 0xf8, 0xd8, 0xf1, 0x97, 0xfc, 0xc1, 0x04, 0xb1, 0xbc, 0xbc, 0xbc, 0x83, 0xb9, + 0xbe, 0xbe, 0xbe, 0xa0, 0xd9, 0xc6, 0xda, 0xde, 0xd8, 0xfc, 0xc2, 0x04, 0xd0, 0xd9, 0xc7, 0xda, + 0xdf, 0xd8, 0x8e, 0xb5, 0xbd, 0x9b, 0xaf, 0x4c, 0xbd, 0xbd, 0x9f, 0xfc, 0xc1, 0x00, 0xd9, 0xf4, + 0x2c, 0xbb, 0xd8, 0xf0, 0xb3, 0x86, 0xb6, 0x9a, 0xbb, 0xab, 0x2c, 0x50, 0x78, 0xf1, 0xba, 0xaa, + 0xc3, 0xc5, 0xc7, 0xb8, 0xad, 0xf8, 0xf9, 0xd1, 0xda, 0xde, 0xb3, 0x8e, 0xbb, 0xab, 0xc7, 0xd8, + 0xb3, 0x8e, 0xb7, 0x9b, 0xba, 0xa7, 0x69, 0xd9, 0xb1, 0x83, 0xb5, 0x90, 0x79, 0xdb, 0xd1, 0xb9, + 0xa0, 0xd0, 0xdf, 0xa1, 0xd0, 0xc6, 0xd8, 0xf4, 0x2c, 0xbb, 0xd8, 0xf1, 0xb0, 0xbc, 0x81, 0xb9, + 0xaf, 0xc0, 0xb0, 0x88, 0xc1, 0x87, 0xc1, 0xb1, 0xbc, 0xbc, 0xbc, 0xb5, 0xbd, 0xbd, 0x9b, 0xfc, + 0xc1, 0x00, 0xbd, 0xbd, 0xdb, 0x9f, 0xfc, 0xc0, 0x04, 0x8f, 0x9e, 0x2d, 0x8d, 0x9f, 0x31, 0xd9, + 0xa1, 0xde, 0x83, 0xa0, 0xc6, 0xaf, 0xde, 0xf8, 0xb3, 0x83, 0x9f, 0xf5, 0x06, 0xf1, 0xdb, 0xfc, + 0xc1, 0x04, 0xd9, 0xb8, 0xbe, 0xa1, 0xdf, 0xf8, 0xbe, 0xbe, 0xbe, 0xd8, 0xf5, 0xb3, 0x89, 0xb7, + 0x93, 0xbb, 0xa9, 0x66, 0x8b, 0xaf, 0x02, 0xf1, 0x9f, 0xfc, 0xc0, 0x03, 0xd9, 0x8f, 0xa9, 0xd0, + 0xc0, 0xd8, 0x89, 0x99, 0xa3, 0x34, 0xaf, 0xde, 0xf8, 0xf5, 0x83, 0x9f, 0x06, 0xf1, 0xfc, 0xc1, + 0x04, 0xdb, 0x95, 0x71, 0xa2, 0xd0, 0xde, 0xd8, 0xb0, 0x8d, 0xb9, 0xa1, 0xd0, 0xc7, 0x8f, 0xb4, + 0x9f, 0xaf, 0x11, 0xd9, 0xa1, 0xd0, 0xc7, 0xd8, 0xf1, 0xb3, 0x89, 0xbb, 0xaf, 0xc6, 0xf9, 0xf5, + /* bank # 45 */ + 0x8f, 0xb7, 0x93, 0x06, 0xf1, 0x9f, 0xfc, 0xc1, 0x03, 0xdb, 0x83, 0xa9, 0xc0, 0xd8, 0xa3, 0xde, + 0xb9, 0xa0, 0xd0, 0xde, 0xba, 0xaa, 0xf8, 0xf9, 0xd1, 0xda, 0xf4, 0x2d, 0x8e, 0xd8, 0xf1, 0xb9, + 0xb1, 0xb5, 0xaf, 0x83, 0x90, 0x61, 0xdb, 0x69, 0x79, 0x91, 0x69, 0xf4, 0x2d, 0x85, 0xd8, 0xf1, + 0xdf, 0xf8, 0xa0, 0xfa, 0xf9, 0xd1, 0xd9, 0xaf, 0xdf, 0xd8, 0xaf, 0x8c, 0x95, 0x69, 0xd9, 0xdf, + 0xd8, 0xaf, 0x85, 0x9c, 0x31, 0xdb, 0x9f, 0xfc, 0xc1, 0x00, 0xda, 0xf4, 0x2d, 0x62, 0xd8, 0xf1, + 0x83, 0xa0, 0xd0, 0xc6, 0xaf, 0x8a, 0x9e, 0x11, 0xf8, 0xd9, 0xa0, 0xd0, 0x80, 0x9c, 0x48, 0xd8, + 0xaa, 0xde, 0xd8, 0xf1, 0xb3, 0x85, 0xb7, 0x95, 0xaf, 0x71, 0xb1, 0xb5, 0xd9, 0xa0, 0xd0, 0xde, + 0xd8, 0xf1, 0x83, 0xaf, 0xc6, 0xf8, 0x8f, 0x94, 0x1d, 0xdb, 0x90, 0xfc, 0xc0, 0x00, 0xa0, 0xd0, + 0xde, 0xd8, 0xf4, 0x2d, 0x8e, 0xd8, 0xf1, 0x61, 0xd1, 0xaa, 0xd9, 0xde, 0xda, 0xf8, 0xd8, 0xf1, + 0xb1, 0x88, 0xbb, 0xa4, 0xd0, 0xc5, 0xa0, 0xd0, 0xc7, 0xb5, 0x90, 0xfc, 0xc2, 0x00, 0xd9, 0xb2, + 0x8e, 0xc6, 0xa4, 0xd0, 0xc5, 0xba, 0xae, 0xde, 0xf4, 0x2d, 0xbd, 0xd8, 0xf1, 0x84, 0xb4, 0x9f, + 0xba, 0xa7, 0x69, 0xda, 0xae, 0xf8, 0xf4, 0x2d, 0xbd, 0xd8, 0xf1, 0xae, 0xde, 0xd8, 0xf1, 0xb1, + 0x81, 0xb5, 0x9e, 0xbb, 0xaf, 0x02, 0xb7, 0x94, 0x26, 0xb3, 0x81, 0xb5, 0x9d, 0xa1, 0x02, 0xb7, + 0x90, 0x26, 0x8f, 0x91, 0xa1, 0x00, 0x2c, 0xb1, 0x80, 0x94, 0xaf, 0x12, 0x26, 0x5e, 0x6e, 0xb3, + 0x80, 0x92, 0xa2, 0x42, 0x0e, 0x76, 0x3e, 0x8f, 0xa2, 0x00, 0x2c, 0x54, 0x7c, 0xaf, 0xde, 0xf8, + 0xf5, 0x8f, 0x99, 0xaf, 0x06, 0xf1, 0x9f, 0xfc, 0xc1, 0x03, 0xd9, 0x8a, 0xaa, 0xc4, 0xd8, 0x83, + /* bank # 46 */ + 0x92, 0xaf, 0x51, 0xd9, 0xf4, 0x2e, 0x4b, 0xd8, 0xf1, 0xa2, 0xd0, 0xde, 0xb6, 0x9e, 0xfc, 0xc0, + 0x09, 0xdb, 0xfc, 0xc1, 0x0a, 0xd9, 0xb8, 0xae, 0xde, 0xba, 0xae, 0xde, 0xfa, 0xb7, 0xbb, 0xf4, + 0x2e, 0x4b, 0xd8, 0xf1, 0xb8, 0xae, 0xde, 0xf8, 0xba, 0xae, 0xdf, 0xf3, 0xbc, 0xbc, 0xbd, 0xbd, + 0xbe, 0xbe, 0xb0, 0xb4, 0xbb, 0xaf, 0xfb, 0xda, 0xb8, 0xa4, 0xd0, 0x8d, 0x94, 0x1d, 0xf1, 0xe2, + 0xd8, 0xf1, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xb3, 0xb7, 0xbb, 0xd8, 0xf1, 0x8a, 0x92, 0xaf, + 0x19, 0xd9, 0xf4, 0x2e, 0x8f, 0xd8, 0xf3, 0xbc, 0xbc, 0xb1, 0x8b, 0xc3, 0xbc, 0xbc, 0xb3, 0xf8, + 0xf9, 0xd1, 0xd9, 0xf4, 0x2e, 0x7d, 0xd8, 0xf1, 0x8e, 0x91, 0x41, 0xd9, 0xf4, 0x2e, 0x7d, 0xd8, + 0xf1, 0x89, 0x93, 0xa3, 0xc6, 0x60, 0x81, 0xa2, 0xd0, 0xc7, 0xf4, 0x2f, 0x0a, 0xd8, 0xf1, 0xa3, + 0xde, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0x8b, 0xaa, 0xc6, 0xf4, 0x2f, 0x0a, 0xd8, + 0xf1, 0x81, 0xaa, 0xc6, 0x9a, 0x60, 0x60, 0xb1, 0x81, 0xb5, 0x93, 0xaf, 0x59, 0xb3, 0xb7, 0xd1, + 0xd9, 0xf4, 0x2f, 0x0a, 0xd8, 0xf1, 0x8a, 0x92, 0xaf, 0x21, 0xda, 0xa3, 0xf8, 0xad, 0xde, 0xd8, + 0x81, 0xaa, 0xc5, 0x85, 0x91, 0xaf, 0x21, 0xd9, 0xf4, 0x2e, 0xe5, 0xd8, 0xf1, 0xa1, 0xdf, 0xa2, + 0xdf, 0xdf, 0x81, 0x95, 0xa5, 0xc7, 0x68, 0x89, 0x93, 0xa3, 0xc6, 0x60, 0xad, 0xf8, 0xaf, 0xde, + 0xf8, 0xf5, 0x89, 0x9f, 0x06, 0xf1, 0xfc, 0xc1, 0x03, 0xdb, 0x8d, 0x9d, 0xaf, 0x21, 0xa3, 0xde, + 0xf8, 0xd8, 0xf4, 0x2f, 0x0a, 0xd8, 0xf1, 0x81, 0xa5, 0xc5, 0x92, 0xaf, 0x49, 0xda, 0xa3, 0xf8, + 0xf8, 0xd8, 0x91, 0xaf, 0x49, 0xda, 0xa3, 0xf8, 0xf8, 0xf8, 0xf8, 0xd8, 0xf1, 0xa3, 0xf8, 0xf9, + /* bank # 47 */ + 0xd1, 0xd9, 0xb1, 0x83, 0xb9, 0xa1, 0xd0, 0xc6, 0xb3, 0xbb, 0xd8, 0xf5, 0x83, 0x9a, 0xaf, 0x1a, + 0xf1, 0xbe, 0xb8, 0xae, 0xc1, 0x89, 0xb5, 0x9e, 0x74, 0xfd, 0x3f, 0xbc, 0xbc, 0xb1, 0x8b, 0x34, + 0xb7, 0x9f, 0xfc, 0xc0, 0x00, 0xbc, 0xbc, 0xbc, 0xb0, 0xbd, 0xb4, 0xd9, 0xf4, 0x2f, 0x64, 0xd8, + 0xf1, 0xa6, 0xf8, 0x86, 0x96, 0xae, 0x11, 0xd9, 0xa6, 0xdf, 0x88, 0xbe, 0xbb, 0xa9, 0xd0, 0xc4, + 0xf2, 0xa1, 0xd0, 0xc6, 0xa2, 0xd0, 0xc6, 0xbe, 0xbe, 0xbe, 0xdb, 0xf1, 0x9e, 0xfc, 0xc3, 0x01, + 0xd9, 0xf2, 0xbe, 0xa1, 0xd0, 0xf8, 0xf8, 0xf8, 0xa2, 0xd0, 0xf8, 0xf8, 0xf8, 0xbe, 0xbe, 0xbe, + 0xd8, 0xf4, 0x2f, 0xa2, 0xd8, 0xf1, 0x9e, 0xfc, 0xc3, 0x01, 0xd9, 0xf5, 0x8e, 0xae, 0x32, 0xf1, + 0xdb, 0xfc, 0xc0, 0x01, 0x88, 0xbe, 0xbb, 0xa9, 0xd0, 0xc4, 0xf2, 0xa1, 0xd0, 0xc6, 0xa2, 0xd0, + 0xc6, 0xbe, 0xbe, 0xbe, 0xf4, 0x2f, 0xa2, 0xd8, 0xf1, 0xa6, 0xfa, 0x86, 0x96, 0xae, 0x39, 0xd9, + 0xa6, 0xde, 0x87, 0xbe, 0xbb, 0xa9, 0xd0, 0xc4, 0xf2, 0xa1, 0xd0, 0xc6, 0xa2, 0xd0, 0xc6, 0xbe, + 0xbe, 0xbe, 0xd8, 0xf1, 0xbc, 0xbc, 0xbc, 0xb3, 0xbd, 0xbd, 0xbd, 0xb7, 0xbe, 0xbe, 0xbe, 0xbb, + 0xa5, 0xf8, 0xf9, 0xd1, 0xda, 0x86, 0xa7, 0xc3, 0xc5, 0xc7, 0xa5, 0xde, 0x85, 0xa5, 0xd0, 0xc6, + 0xd8, 0x85, 0x95, 0xaf, 0x71, 0xda, 0xf4, 0x2f, 0xe2, 0xd8, 0xf1, 0x89, 0x93, 0xa3, 0x60, 0xf3, + 0xbe, 0xbe, 0xaf, 0xf8, 0xf9, 0xd1, 0xda, 0xf3, 0xe2, 0xd8, 0xf1, 0xbe, 0xbe, 0x86, 0xa7, 0xc3, + 0xc5, 0xc7, 0xd8, 0xf1, 0xaf, 0xdf, 0xf9, 0x89, 0x9f, 0x2d, 0x83, 0x0d, 0xf5, 0x99, 0xaf, 0x1a, + 0x8f, 0x7e, 0x9f, 0xa8, 0x12, 0x99, 0x2e, 0xf1, 0xdf, 0xdf, 0xaf, 0xdf, 0xf9, 0x89, 0x9f, 0x4d, + /* bank # 48 */ + 0x83, 0x0d, 0xf5, 0x9b, 0xaf, 0x02, 0x8f, 0x66, 0xf1, 0x9f, 0xfc, 0xc0, 0x03, 0xd9, 0xf5, 0xa8, + 0xd0, 0x12, 0x99, 0x36, 0xd8, 0xf1, 0x88, 0x98, 0xa6, 0x10, 0xa7, 0x38, 0x86, 0x9f, 0xaf, 0xde, + 0x00, 0xfd, 0x08, 0x87, 0x00, 0x8f, 0xf3, 0xae, 0xc0, 0xf1, 0xbc, 0xbc, 0xb1, 0x82, 0xc3, 0xbc, + 0xbc, 0xd8, 0xf3, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xbb, 0xb3, 0xb7, 0xa2, 0xf8, 0xf2, 0xf8, + 0xf1, 0x80, 0x9d, 0xad, 0xd0, 0x7c, 0xf2, 0xa2, 0xfa, 0xf9, 0xd1, 0xf1, 0xb9, 0xac, 0xd9, 0xde, + 0xda, 0xf8, 0xd8, 0xf5, 0xbe, 0xbe, 0xba, 0xa7, 0x85, 0x95, 0x78, 0x8e, 0x9e, 0x7c, 0xbc, 0xbc, + 0xbd, 0xbd, 0xb2, 0xb6, 0xf1, 0xa9, 0x89, 0x99, 0x62, 0xf0, 0x97, 0x40, 0x99, 0x6c, 0x97, 0x48, + 0xb9, 0xb1, 0xb5, 0xf1, 0xaf, 0x80, 0x91, 0x28, 0x8c, 0x9f, 0x00, 0x83, 0x65, 0xd9, 0xf4, 0x30, + 0x94, 0xd8, 0xf1, 0x9d, 0xfc, 0xc3, 0x04, 0xaf, 0xb2, 0x89, 0xd9, 0xc3, 0xc1, 0xda, 0xc1, 0xc3, + 0xd8, 0xf4, 0x75, 0x55, 0xd8, 0xf2, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xb9, 0xb3, 0xb7, 0xa6, + 0x81, 0x92, 0x49, 0xf9, 0xdb, 0xf1, 0xb1, 0x8c, 0xb5, 0x9c, 0x21, 0xd9, 0xf5, 0xb3, 0x85, 0xb7, + 0x95, 0x78, 0x8e, 0x9e, 0x7c, 0xf1, 0xb1, 0x8d, 0xb5, 0x9d, 0xad, 0x1a, 0xf0, 0x96, 0x40, 0x9d, + 0x3c, 0x96, 0x48, 0xd8, 0xf1, 0xb1, 0x81, 0xb5, 0x9d, 0xb9, 0xa6, 0x0a, 0x8d, 0x96, 0x05, 0xd9, + 0xf4, 0x30, 0xfb, 0xd8, 0xf2, 0xb3, 0x81, 0xb7, 0x92, 0xbb, 0xaf, 0x49, 0xf9, 0xf9, 0xdb, 0xf1, + 0xb1, 0x8c, 0xb5, 0x9c, 0xb9, 0xa6, 0x21, 0xf4, 0x30, 0xfb, 0xd8, 0xf1, 0xb3, 0x8e, 0xbb, 0xa8, + 0xd0, 0xc4, 0xc7, 0xf3, 0xb9, 0xac, 0xd0, 0xde, 0xf4, 0x31, 0x0c, 0xd8, 0xf1, 0xb3, 0x85, 0xbb, + /* bank # 49 */ + 0xa8, 0xd0, 0xc4, 0xc7, 0xf3, 0xb9, 0xac, 0xd0, 0xde, 0xf8, 0xdf, 0xf8, 0xd8, 0xf3, 0xb5, 0x9c, + 0xfc, 0xc3, 0x04, 0xdb, 0xfc, 0xc2, 0x00, 0xd9, 0xf2, 0xac, 0xd0, 0xde, 0xd8, 0xf2, 0xbb, 0xaf, + 0xb7, 0x92, 0xb3, 0x82, 0x19, 0xdb, 0xa2, 0xdf, 0xa1, 0xd0, 0xc4, 0xac, 0xd0, 0xc5, 0xf3, 0xa7, + 0xd0, 0xdf, 0xf1, 0xb9, 0xaa, 0xde, 0xa1, 0xdf, 0xb5, 0x9b, 0xfc, 0xc1, 0x00, 0xb8, 0xbe, 0xa7, + 0xd0, 0xde, 0xbe, 0xbe, 0xbe, 0xd8, 0xf1, 0xbb, 0xaf, 0x89, 0xb7, 0x98, 0x19, 0xa9, 0x80, 0xd9, + 0x38, 0xd8, 0xaf, 0x89, 0x39, 0xa9, 0x80, 0xda, 0x3c, 0xd8, 0xa1, 0xf8, 0xf9, 0xd1, 0xda, 0xf9, + 0xdf, 0xf8, 0xf4, 0x75, 0x3d, 0xf1, 0xff, 0xd8, 0xaf, 0x2e, 0x88, 0xf5, 0x75, 0xda, 0xff, 0xd8, + 0x71, 0xda, 0xf1, 0xff, 0xd8, 0x82, 0xa7, 0xf3, 0xc1, 0xf2, 0x80, 0xc2, 0xf1, 0x97, 0x86, 0x49, + 0x2e, 0xa6, 0xd0, 0x50, 0x96, 0x86, 0xaf, 0x75, 0xd9, 0x88, 0xa2, 0xd0, 0xf3, 0xc0, 0xc3, 0xf1, + 0xda, 0x8f, 0x96, 0xa2, 0xd0, 0xf3, 0xc2, 0xc3, 0x82, 0xb6, 0x9b, 0x70, 0x70, 0xf1, 0xd8, 0xb7, + 0xaf, 0xdf, 0xf9, 0x89, 0x99, 0xaf, 0x10, 0x80, 0x9f, 0x21, 0xda, 0x2e, 0xd8, 0x89, 0x99, 0xaf, + 0x31, 0xda, 0xdf, 0xd8, 0xaf, 0x82, 0x92, 0xf3, 0x41, 0xd9, 0xf1, 0xdf, 0xd8, 0xaf, 0x82, 0xf3, + 0x19, 0xd9, 0xf1, 0xdf, 0xd8, 0xf1, 0x89, 0x90, 0xaf, 0xd0, 0x09, 0x8f, 0x99, 0xaf, 0x51, 0xdb, + 0x89, 0x31, 0xf3, 0x82, 0x92, 0x19, 0xf2, 0xb1, 0x8c, 0xb5, 0x9c, 0x71, 0xd9, 0xf1, 0xdf, 0xf9, + 0xf2, 0xb9, 0xac, 0xd0, 0xf8, 0xf8, 0xf3, 0xdf, 0xd8, 0xb3, 0xb7, 0xbb, 0x82, 0xac, 0xf3, 0xc0, + 0xa2, 0x80, 0x22, 0xf1, 0xa9, 0x22, 0x26, 0x9f, 0xaf, 0x29, 0xda, 0xac, 0xde, 0xff, 0xd8, 0xa2, + /* bank # 50 */ + 0xf2, 0xde, 0xf1, 0xa9, 0xdf, 0xf2, 0x82, 0xb8, 0xbe, 0xa9, 0xc3, 0x81, 0xc5, 0xb0, 0xbc, 0xf1, + 0xb5, 0x9b, 0xfc, 0xc1, 0x03, 0xb4, 0xbd, 0xd9, 0xf4, 0x32, 0x33, 0xd8, 0xf2, 0x89, 0x99, 0xa9, + 0x49, 0xda, 0xf4, 0x32, 0x33, 0xd8, 0xf1, 0x9a, 0xfc, 0xc0, 0x04, 0xa7, 0xd0, 0xd9, 0x88, 0x97, + 0x30, 0xda, 0xde, 0xd8, 0xf1, 0xbc, 0xb1, 0x80, 0xbb, 0xbe, 0xbe, 0xbe, 0xaf, 0xc2, 0x8c, 0xc1, + 0x81, 0xc3, 0x83, 0xc7, 0xbc, 0xbc, 0xb3, 0x8f, 0xb7, 0xbd, 0xbd, 0xbd, 0x9f, 0xba, 0xa7, 0x61, + 0xdb, 0x69, 0x71, 0xff, 0xd8, 0xf1, 0xbb, 0xad, 0xd0, 0xde, 0xf8, 0xb1, 0x84, 0xb6, 0x96, 0xba, + 0xa7, 0xd0, 0x7e, 0xb7, 0x96, 0xa7, 0x01, 0xb2, 0x87, 0x9d, 0x05, 0xdb, 0xb3, 0x8d, 0xb6, 0x97, + 0x79, 0xf3, 0xb1, 0x8c, 0x96, 0x49, 0xf1, 0xbb, 0xad, 0xd0, 0xf8, 0xd8, 0xf3, 0xb9, 0xac, 0xd0, + 0xf8, 0xf9, 0xd1, 0xd9, 0xf1, 0xbb, 0xad, 0xd0, 0xf8, 0xd8, 0xb3, 0xb7, 0xbb, 0x97, 0x8c, 0xaf, + 0xf3, 0x79, 0xd9, 0xf4, 0x32, 0xa6, 0xd8, 0xf1, 0xa1, 0x81, 0x9d, 0x34, 0xaa, 0xd0, 0x8a, 0x50, + 0xf4, 0x75, 0x3d, 0xf4, 0x32, 0xc6, 0xd8, 0xf3, 0xa7, 0xd0, 0xfa, 0xb5, 0x9c, 0xfc, 0xc2, 0x07, + 0xd9, 0xf8, 0xd8, 0xb7, 0x97, 0x8c, 0xaf, 0x79, 0xda, 0xf1, 0x87, 0x91, 0xa1, 0x6c, 0xaa, 0xd0, + 0x9a, 0x70, 0xbb, 0xf4, 0x75, 0x3d, 0xd8, 0xf1, 0x91, 0xfc, 0xc1, 0x0a, 0xd9, 0xf4, 0x33, 0x07, + 0xd8, 0xf1, 0x81, 0xa1, 0xc2, 0xf9, 0xdf, 0xf8, 0x80, 0x9d, 0xba, 0xa6, 0xd0, 0x38, 0xfd, 0x31, + 0xbb, 0xaf, 0xde, 0xf3, 0x82, 0xce, 0xf1, 0x8f, 0x90, 0x08, 0xfd, 0x0f, 0x8d, 0x9f, 0x65, 0xd9, + 0xf4, 0x33, 0x07, 0xd8, 0xf1, 0xaf, 0xde, 0xf2, 0x8c, 0xce, 0xf2, 0x82, 0x9f, 0x25, 0xd9, 0xf1, + /* bank # 51 */ + 0xba, 0xa6, 0xd0, 0xde, 0xf3, 0x8d, 0xce, 0xd8, 0xf1, 0xb5, 0x9b, 0xfc, 0xc1, 0x03, 0xd9, 0xbc, + 0xbd, 0xbe, 0xf4, 0x33, 0x3b, 0xd8, 0xf1, 0xb8, 0xbe, 0xaa, 0xd0, 0xde, 0xf2, 0xb3, 0x81, 0xb7, + 0x92, 0xa9, 0x49, 0xd9, 0xbc, 0xbd, 0xf4, 0x33, 0x3b, 0xd8, 0xf1, 0xbc, 0xbd, 0xb0, 0xb4, 0x8d, + 0x97, 0x31, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xd9, 0xaa, 0xd0, 0xf8, 0xd8, 0xf1, 0xbc, 0xbc, 0xbd, + 0xbd, 0xbe, 0xbe, 0xb0, 0x84, 0xb8, 0xa5, 0xc3, 0xc5, 0xc7, 0x83, 0xa4, 0xc3, 0xc5, 0xc7, 0xf0, + 0xb2, 0x81, 0xb6, 0x91, 0xa3, 0x3c, 0x11, 0x0c, 0x58, 0x2c, 0x50, 0xf1, 0xb0, 0x83, 0xb4, 0x93, + 0xa3, 0x2c, 0x54, 0x7c, 0x92, 0x71, 0xf0, 0x95, 0xae, 0x2c, 0x50, 0x78, 0x8e, 0xbe, 0xb9, 0xaa, + 0xc2, 0xbc, 0xbd, 0xd8, 0xf2, 0xbb, 0xb3, 0xb7, 0x82, 0x91, 0xaf, 0x31, 0xda, 0xf4, 0x33, 0xdf, + 0xd8, 0xf1, 0x8d, 0xb7, 0x96, 0xbb, 0xa6, 0x40, 0xac, 0x8c, 0x9c, 0x0c, 0x30, 0xba, 0x8d, 0x9d, + 0xa7, 0x39, 0xdb, 0xf3, 0xb1, 0x8c, 0xb6, 0x96, 0x49, 0xd9, 0xf1, 0x84, 0xb5, 0x94, 0xb9, 0xa4, + 0xd0, 0x5e, 0xf0, 0xb7, 0x9d, 0x38, 0xd8, 0xf1, 0xb3, 0x8d, 0xba, 0xa7, 0xc6, 0xb5, 0x9c, 0xfc, + 0xc2, 0x04, 0xd9, 0xb1, 0x81, 0xb6, 0x97, 0xa7, 0x25, 0x8b, 0x6e, 0x81, 0xb9, 0xa1, 0x34, 0xda, + 0xb2, 0x87, 0xb6, 0x97, 0x00, 0xfd, 0x3e, 0xb1, 0x81, 0x25, 0x8b, 0x4e, 0x81, 0xb9, 0xa1, 0x34, + 0xd8, 0xf1, 0xbb, 0xaa, 0xd0, 0xdf, 0xac, 0xde, 0xd0, 0xde, 0xad, 0xd0, 0xdf, 0xf1, 0xff, 0xd8, + 0xf2, 0xb3, 0xb7, 0xaf, 0x82, 0x9c, 0x39, 0xdb, 0xf1, 0x86, 0x90, 0x09, 0xaa, 0xd0, 0x8a, 0x9d, + 0xd9, 0x74, 0xf4, 0x33, 0xfa, 0xda, 0xf1, 0xaa, 0xd0, 0xdf, 0xd8, 0xf3, 0xb9, 0xac, 0xd0, 0xf8, + /* bank # 52 */ + 0xf9, 0xd1, 0xd9, 0xf2, 0xbb, 0xa2, 0xfa, 0xf8, 0xda, 0xf2, 0xbb, 0xa2, 0xfa, 0xd8, 0xf2, 0xb3, + 0x82, 0xb6, 0x9b, 0xbb, 0xaf, 0x31, 0xdb, 0xf1, 0x89, 0xb5, 0x9a, 0x61, 0xd9, 0xf2, 0xa1, 0xd0, + 0xf8, 0xf8, 0xd8, 0xf2, 0x82, 0xaf, 0xc4, 0xf8, 0xf8, 0xf8, 0xf8, 0x8f, 0xb7, 0x91, 0x15, 0xda, + 0xa1, 0xd0, 0xc0, 0xd8, 0x82, 0xaf, 0xc2, 0xf9, 0xd1, 0xd9, 0xf1, 0xb9, 0xac, 0xde, 0xad, 0xde, + 0xdf, 0xb9, 0xa1, 0xdf, 0xbb, 0xad, 0xd0, 0xdf, 0xd8, 0xf2, 0x82, 0x91, 0xaf, 0x31, 0xda, 0xf1, + 0xb1, 0x81, 0x9d, 0xb9, 0xa1, 0x3c, 0xd8, 0xf2, 0xb3, 0xbb, 0x82, 0x91, 0xaf, 0x31, 0xd1, 0xd9, + 0xf1, 0xb1, 0x81, 0xb5, 0x9b, 0xb9, 0xa1, 0x3e, 0xd8, 0xf1, 0xb3, 0x8c, 0xb7, 0x9c, 0xbb, 0xac, + 0xd0, 0x10, 0xac, 0xde, 0xad, 0xd0, 0xdf, 0x92, 0x82, 0xaf, 0xf1, 0xca, 0xf2, 0x91, 0x35, 0xf1, + 0x96, 0x8f, 0xa6, 0xd9, 0x00, 0xdb, 0xaf, 0x8a, 0x90, 0x6d, 0xd9, 0xa6, 0x8f, 0x96, 0x01, 0x8a, + 0x60, 0xaa, 0xd0, 0xdf, 0xf2, 0x81, 0xac, 0xd0, 0xc5, 0xd8, 0xf1, 0xff, 0xd8, 0xf0, 0xb9, 0xb1, + 0xb6, 0xaf, 0x8d, 0x92, 0x4c, 0x71, 0x54, 0x68, 0x5c, 0x60, 0x44, 0x79, 0xe0, 0xd8, 0xf1, 0xba, + 0xb1, 0xa4, 0x8f, 0xc0, 0xc3, 0xc5, 0xc7, 0xb9, 0xb5, 0xf1, 0xaa, 0x82, 0x90, 0x25, 0xf3, 0xad, + 0xdf, 0xd9, 0xf8, 0xf8, 0xd8, 0xf1, 0xa1, 0x81, 0x91, 0xf0, 0x34, 0x82, 0x38, 0xf1, 0xaa, 0x2d, + 0xf5, 0x8a, 0x90, 0x30, 0xd9, 0xf3, 0xad, 0xfa, 0xd8, 0xf0, 0xaa, 0x8f, 0x9f, 0x04, 0x28, 0x51, + 0x79, 0x1d, 0x30, 0x14, 0x38, 0xbc, 0xbc, 0xbc, 0xa2, 0xd0, 0x8a, 0x9a, 0x2c, 0x50, 0x50, 0x78, + 0x78, 0xbc, 0x82, 0x90, 0xaa, 0xf5, 0x7c, 0xf3, 0xd9, 0xad, 0xfa, 0xd8, 0xf1, 0xb8, 0xae, 0x82, + /* bank # 53 */ + 0xc6, 0xb9, 0xa1, 0x81, 0x90, 0x0a, 0x81, 0x92, 0x18, 0xa2, 0xd0, 0x81, 0xc1, 0xf3, 0xad, 0xfb, + 0xf9, 0xf1, 0xda, 0xa2, 0xd0, 0xdf, 0xd8, 0xa2, 0xd0, 0xfa, 0xf9, 0xd1, 0xda, 0xaa, 0x82, 0x9d, + 0x7e, 0x76, 0xad, 0x8a, 0xd0, 0x31, 0x5c, 0xf0, 0xaa, 0x8d, 0x9d, 0x54, 0x78, 0xfd, 0x7f, 0xf1, + 0x8a, 0x92, 0x55, 0x9d, 0xad, 0xd0, 0x72, 0x7e, 0xd8, 0xf4, 0x74, 0x9c, 0xe0, 0xd8, 0xf1, 0xb1, + 0xb9, 0x82, 0xa2, 0xd0, 0xc2, 0xf2, 0xa3, 0xfa, 0xf3, 0xb8, 0xa7, 0xf8, 0xf9, 0xd1, 0xda, 0xf2, + 0xe2, 0xd8, 0xbb, 0xb3, 0xe0, 0xf1, 0xb1, 0xaf, 0x8f, 0x9f, 0x31, 0x85, 0xa5, 0xd0, 0xda, 0xc6, + 0xf4, 0x35, 0x72, 0xd8, 0xf1, 0xf8, 0xf9, 0xd1, 0xd9, 0xc6, 0xf5, 0xad, 0xd0, 0x8d, 0x9e, 0x7f, + 0xda, 0xf9, 0xd8, 0xf1, 0xe0, 0xf1, 0xb6, 0x97, 0xa7, 0x66, 0xb7, 0x93, 0xf0, 0x71, 0x71, 0x60, + 0xe0, 0xf0, 0x01, 0x29, 0x51, 0x79, 0xe0, 0xf1, 0xc2, 0xc5, 0xc7, 0xb2, 0x87, 0xb6, 0x97, 0x2c, + 0xfd, 0x01, 0xe0, 0xf1, 0xc2, 0xc5, 0xc7, 0xb2, 0x87, 0xc1, 0xe0, 0xf1, 0xb2, 0x81, 0x97, 0x66, + 0xe0, 0xf0, 0x38, 0x10, 0x28, 0x40, 0x88, 0xe0, 0xf0, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38, 0x64, + 0x48, 0x31, 0x2d, 0x51, 0x79, 0xe0, 0xf0, 0x24, 0x58, 0x3d, 0x40, 0x34, 0x49, 0x2d, 0x51, 0xe0, + 0xf1, 0x87, 0xa1, 0x00, 0x2c, 0x54, 0x7c, 0xf0, 0x81, 0xa7, 0x04, 0x28, 0x50, 0x78, 0xfd, 0x7f, + 0xf1, 0xa7, 0x87, 0x96, 0x59, 0x91, 0xa1, 0x02, 0x0e, 0x16, 0x1e, 0xe0, 0xd8, 0xf0, 0xbe, 0xbe, + 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xb3, 0xbb, 0x8c, 0xac, 0xf4, 0x78, 0x59, 0x8d, 0xad, + 0xf4, 0x78, 0x59, 0x8e, 0xae, 0xf4, 0x78, 0x59, 0xbc, 0xb0, 0x80, 0xba, 0xaf, 0xf1, 0xde, 0xdf, + /* bank # 54 */ + 0xdf, 0xd0, 0xf2, 0xc2, 0xcb, 0xc5, 0xbc, 0xbc, 0xbc, 0xb2, 0x8f, 0xd0, 0xbd, 0xb5, 0x9e, 0xf1, + 0x02, 0xfd, 0x03, 0x26, 0xfd, 0x03, 0x46, 0xfd, 0x03, 0xbd, 0xbd, 0xbd, 0xb5, 0x90, 0xbb, 0xaf, + 0x02, 0xf0, 0x28, 0x50, 0xf1, 0x1e, 0x91, 0xf0, 0x20, 0x48, 0xf1, 0x16, 0xf0, 0x38, 0x92, 0x40, + 0xb3, 0xb7, 0x8f, 0xf2, 0xac, 0xc0, 0xad, 0xc2, 0xae, 0xc4, 0xf1, 0xa9, 0xfa, 0xf9, 0xd1, 0xd9, + 0xf4, 0x36, 0x4a, 0xd8, 0xf1, 0xa9, 0xfa, 0xf4, 0x38, 0x1c, 0xd8, 0xf0, 0xb7, 0x8c, 0x9c, 0xba, + 0xf4, 0x78, 0x28, 0xf1, 0xc1, 0xb3, 0x8d, 0x9d, 0xba, 0xf4, 0x78, 0x28, 0xf1, 0x1c, 0xb3, 0x8e, + 0x9e, 0xba, 0xf4, 0x78, 0x28, 0xf1, 0x1c, 0xb3, 0x8f, 0xd7, 0xfd, 0x3e, 0xf2, 0x8d, 0xc1, 0x8e, + 0xc1, 0xf1, 0x8f, 0xd5, 0xfd, 0x30, 0xd4, 0xd0, 0xfd, 0x70, 0xf1, 0xd0, 0x2a, 0xd2, 0xf0, 0x00, + 0xd2, 0xa9, 0xde, 0x8f, 0xb5, 0x97, 0xaf, 0xf5, 0x40, 0xd9, 0xf2, 0xa9, 0xf8, 0xd8, 0x97, 0xaf, + 0xf5, 0x48, 0xd9, 0xf3, 0xa9, 0xf8, 0xd8, 0xf2, 0xaf, 0xde, 0xf8, 0xd4, 0xfd, 0x0c, 0xb7, 0x8f, + 0x9d, 0x05, 0xda, 0xf4, 0x36, 0xc3, 0xd8, 0xf2, 0xb5, 0x97, 0xde, 0xf8, 0xd0, 0x37, 0xfd, 0x0e, + 0x3f, 0xfd, 0x0e, 0x8d, 0xb7, 0x9f, 0xd0, 0x05, 0xd9, 0xa9, 0xf8, 0xd8, 0xaf, 0x0d, 0xd9, 0xa9, + 0xf3, 0xf8, 0xd8, 0xd8, 0xf2, 0xaf, 0xde, 0xf8, 0xd4, 0xfd, 0x0c, 0x8f, 0x9e, 0x05, 0xda, 0xf4, + 0x36, 0xee, 0xd8, 0xf2, 0xb5, 0x97, 0xde, 0xf8, 0xd0, 0x37, 0xfd, 0x0e, 0x3f, 0xfd, 0x0e, 0x8e, + 0xb7, 0x9f, 0xd0, 0x05, 0xd9, 0xa9, 0xf8, 0xd8, 0xaf, 0x0d, 0xd9, 0xa9, 0xf3, 0xf8, 0xd8, 0xf1, + 0x8c, 0xaf, 0xde, 0xf2, 0xc0, 0x8f, 0xf0, 0xd4, 0xfd, 0x30, 0x9f, 0xf5, 0x00, 0xb1, 0x88, 0x04, + /* bank # 55 */ + 0xd9, 0xa9, 0xf2, 0xf8, 0xd8, 0xf5, 0xaf, 0x24, 0xd9, 0xa9, 0xf3, 0xf8, 0xd8, 0xf0, 0xaf, 0xb3, + 0x89, 0xc4, 0xc7, 0x8f, 0xd0, 0xd4, 0xfd, 0x40, 0xd5, 0xfd, 0x40, 0xb1, 0x88, 0xd0, 0xf5, 0x44, + 0xd9, 0xa9, 0xf2, 0xf8, 0xd8, 0xaf, 0xf5, 0x6c, 0xd9, 0xa9, 0xf3, 0xf8, 0xd8, 0xb3, 0x8f, 0xb5, + 0x99, 0xf5, 0xaf, 0x60, 0xd9, 0xaa, 0xf8, 0xf4, 0x37, 0x45, 0xd8, 0xf1, 0xb1, 0x8a, 0xb7, 0x9f, + 0xaf, 0x59, 0xd9, 0xaa, 0xde, 0xd8, 0xf5, 0xb3, 0x8f, 0xb5, 0x99, 0xaf, 0x68, 0xd9, 0xaa, 0xfa, + 0xda, 0xaa, 0xdf, 0xd8, 0xf1, 0x8a, 0xaf, 0xd4, 0xfd, 0x00, 0xd5, 0xfd, 0x40, 0x8f, 0xd0, 0xf5, + 0x14, 0xa9, 0xd0, 0xd9, 0xde, 0xda, 0xf8, 0xd8, 0xaf, 0x3c, 0xa9, 0xd0, 0xd9, 0xdf, 0xda, 0xfa, + 0xd8, 0xf1, 0x8a, 0xaf, 0xd6, 0xfd, 0x00, 0xd7, 0xfd, 0x40, 0x8f, 0x9a, 0xd0, 0xf5, 0x04, 0xa9, + 0xd9, 0xf2, 0xf8, 0xd8, 0xaf, 0xf5, 0x2c, 0xa9, 0xd9, 0xf3, 0xf8, 0xd8, 0x8c, 0xaf, 0xf2, 0xc0, + 0xf1, 0x8f, 0xd4, 0xfd, 0x30, 0xb7, 0x9f, 0x02, 0xfd, 0x1e, 0xd0, 0x10, 0xaf, 0xde, 0xf8, 0xf8, + 0xf8, 0xf8, 0xf8, 0xf8, 0xbd, 0xbd, 0xbd, 0x93, 0xf5, 0x02, 0xf1, 0xbd, 0xf8, 0xf9, 0xd1, 0xda, + 0xf4, 0x37, 0xbd, 0xd8, 0xf1, 0xb1, 0x8a, 0x9f, 0x59, 0xda, 0xf4, 0x37, 0xd3, 0xd8, 0xf1, 0xb1, + 0x8b, 0x9f, 0xaf, 0x51, 0xda, 0xf4, 0x37, 0xd3, 0xd8, 0xf1, 0xb5, 0x9b, 0xb3, 0x8f, 0x41, 0xd9, + 0xa9, 0xf2, 0xf8, 0xd8, 0xf1, 0xaf, 0xb7, 0x9f, 0xb1, 0x8a, 0x79, 0xda, 0xf4, 0x37, 0xf2, 0xd8, + 0xf1, 0x8b, 0x71, 0xda, 0xf4, 0x37, 0xf2, 0xd8, 0xf1, 0xb5, 0x9b, 0xb3, 0x8f, 0x49, 0xd9, 0xa9, + 0xf3, 0xf8, 0xd8, 0xf0, 0xa9, 0xf2, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xaa, 0xd0, 0xf0, + /* bank # 56 */ + 0xda, 0xde, 0xf5, 0xe2, 0xf0, 0xd9, 0xf8, 0xd8, 0xa9, 0xf3, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, + 0xf9, 0xaa, 0xd0, 0xf0, 0xda, 0xdf, 0xf6, 0xe2, 0xf0, 0xd9, 0xfa, 0xd8, 0xd8, 0xf0, 0xbc, 0xb0, + 0x80, 0xbd, 0xb4, 0x90, 0xbe, 0xb8, 0xa0, 0xe0, 0xf0, 0xaf, 0xf2, 0x11, 0x3d, 0xf3, 0x15, 0x3d, + 0xf2, 0xb2, 0x8f, 0xd0, 0xcd, 0xcf, 0xf3, 0xdf, 0xdf, 0xdf, 0xdf, 0xf1, 0xd4, 0xfd, 0x70, 0xd5, + 0xfd, 0x70, 0xd6, 0xfd, 0x70, 0xd7, 0xfd, 0x70, 0xb6, 0x9f, 0x0c, 0x10, 0x18, 0xf5, 0x00, 0xb5, + 0x96, 0xf5, 0x18, 0xbb, 0xaf, 0xd0, 0xb7, 0x9f, 0xe0, 0xf0, 0xd0, 0xf3, 0xcf, 0xf2, 0xcc, 0xd0, + 0xf3, 0xcd, 0xf2, 0xca, 0xd0, 0xf3, 0xcb, 0xf2, 0xc8, 0xd0, 0xf3, 0xc9, 0xe0 \ No newline at end of file diff --git a/src/util/icm20948_img.dmp3a.h b/src/util/icm20948_img.dmp3a.h new file mode 100644 index 0000000..834203e --- /dev/null +++ b/src/util/icm20948_img.dmp3a.h @@ -0,0 +1,951 @@ + /* bank # 0 */ + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x05, 0x00, 0x00, 0x00, 0x05, 0x00, 0x00, 0x00, 0x05, 0x00, 0x01, 0x00, 0x05, 0x00, 0xff, + 0xff, 0xf7, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, + 0x80, 0x00, 0x80, 0x00, 0x40, 0x00, 0x40, 0x00, 0x20, 0x00, 0x20, 0x00, 0x10, 0x00, 0x10, 0x00, + 0x08, 0x00, 0x08, 0x00, 0x04, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x00, 0x01, 0x00, 0x01, 0x00, + 0x00, 0x80, 0x00, 0x80, 0x00, 0x40, 0x00, 0x40, 0x00, 0x20, 0x00, 0x20, 0x00, 0x10, 0x00, 0x10, + 0x00, 0x08, 0x00, 0x08, 0x00, 0x04, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x00, 0x01, 0x00, 0x01, + /* bank # 1 */ + 0x00, 0x00, 0x03, 0x84, 0x00, 0x00, 0x9c, 0x40, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, + 0x36, 0x66, 0x66, 0x66, 0x00, 0x0f, 0x00, 0x00, 0x13, 0x5c, 0x28, 0xf6, 0x0c, 0xf5, 0xc2, 0x8f, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xff, 0xf8, 0x00, 0x38, + 0x09, 0xed, 0xd1, 0xe8, 0x00, 0x00, 0x68, 0x00, 0x00, 0x01, 0xff, 0xc7, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x01, 0x47, 0xae, 0x14, 0x3e, 0xb8, 0x51, 0xec, 0x00, 0x0f, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x0c, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x15, 0x55, 0x55, 0x55, 0x0a, 0xaa, 0xaa, 0xaa, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe1, 0x00, 0x00, 0x00, 0x01, 0x00, 0x06, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x48, 0xd1, 0x59, 0x3f, 0xb7, 0x2e, 0xa7, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x8e, 0x17, 0x00, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x20, + /* bank # 2 */ + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7f, 0xff, 0x00, 0x00, 0x00, 0x05, 0x21, 0xe9, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x3e, 0x03, 0x30, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x03, 0x00, 0x0a, 0x01, 0x2b, 0x4a, 0xee, + 0x06, 0x54, 0xad, 0x11, 0xe3, 0x07, 0x5c, 0x15, 0x36, 0x2b, 0xd0, 0x26, 0xd0, 0x8c, 0x49, 0xa4, + 0x06, 0x54, 0xad, 0x11, 0x1e, 0x0b, 0xb5, 0x55, 0x38, 0xee, 0x17, 0x50, 0x31, 0x36, 0x3f, 0x03, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 3 */ + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x80, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x00, 0x00, 0x0e, 0x35, 0x75, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x10, 0x00, 0x96, 0x00, 0x3c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0d, 0x72, 0xaa, 0x29, 0xc9, 0x3d, 0x6c, 0x4e, 0x55, 0x16, 0x4c, 0x7f, 0xc4, 0x42, 0x74, 0x97, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x3d, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x31, 0x88, 0x15, 0xe3, 0xa3, 0x40, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0e, 0x70, 0x4b, 0x8c, 0xc5, 0x0a, 0x92, 0xbe, 0x5a, 0x96, 0x91, 0xd2, 0xc1, 0xee, 0xe7, 0x0d, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x02, + 0x00, 0x00, 0x00, 0x14, 0x00, 0x2d, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 4 */ + 0x00, 0x00, 0x00, 0xa3, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x3a, 0x03, 0xe8, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x26, 0x00, 0x00, 0x00, 0x02, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x3f, 0xc1, 0xa7, 0x68, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x33, 0x33, 0x33, 0x33, 0x0c, 0xcc, 0xcc, 0xcd, + 0x00, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x18, + 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x64, 0x87, 0xed, 0x51, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x64, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x01, 0x1d, 0xf4, 0x6a, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x02, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x00, 0x7f, 0xff, 0x00, 0x00, 0x20, 0x00, + /* bank # 5 */ + 0x00, 0x00, 0x9c, 0x40, 0x0c, 0xcc, 0xcc, 0xcd, 0x00, 0x00, 0x07, 0x80, 0x00, 0x02, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3e, 0xb8, 0x51, 0xec, 0x01, 0x47, 0xae, 0x14, + 0x00, 0x00, 0x01, 0x5e, 0x00, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x10, 0x00, 0x00, + 0x00, 0x00, 0x61, 0xa8, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x10, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, 0x2e, 0xe0, 0x00, 0x06, 0x40, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, + 0x03, 0xff, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x33, 0x33, 0x33, 0x33, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0c, 0xcc, 0xcc, 0xcd, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x9d, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 6 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x49, 0x1b, 0x75, + 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x40, 0x00, 0x00, 0x0c, 0xcd, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 7 */ + 0x00, 0x00, 0x50, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x16, 0x00, 0x00, 0x00, 0x00, 0x46, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xd4, 0xc0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, 0x01, 0x3c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 8 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x28, 0x00, 0x00, 0x3a, 0x98, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x01, 0x4e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x47, 0xae, 0x14, 0x4e, 0x40, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0c, 0x00, 0x00, 0x20, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0d, 0x06, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x27, 0x10, + 0x00, 0x00, 0x00, 0x00, 0x4a, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0e, 0xd8, 0x00, 0x00, 0x01, 0x18, 0x00, 0x00, 0x07, 0xd0, + /* bank # 9 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x27, 0x10, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x13, 0x1b, + 0x00, 0x0b, 0xb8, 0x00, 0x00, 0x3c, 0xbf, 0x0f, 0x00, 0x55, 0xce, 0x75, 0x00, 0x00, 0x27, 0x10, + 0x05, 0xb0, 0x5b, 0x05, 0x3a, 0x4f, 0xa4, 0xfa, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x00, 0x00, 0x00, 0x3c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5a, 0x00, 0x1d, 0x20, 0x8a, 0x00, 0x61, 0x93, 0x69, + 0x00, 0x00, 0x01, 0x3c, 0x00, 0x00, 0x4d, 0xf0, 0x00, 0x55, 0xce, 0x75, 0x00, 0x00, 0x02, 0x76, + 0x06, 0x66, 0x66, 0x66, 0x39, 0x99, 0x99, 0x99, 0x10, 0x00, 0x00, 0x00, 0x30, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x0c, 0xcc, 0xcc, 0xcc, 0x33, 0x33, 0x33, 0x33, 0x00, 0x0e, 0x90, 0x45, + 0x00, 0x00, 0x00, 0x00, 0x01, 0xd4, 0x1d, 0x41, 0x3e, 0x2b, 0xe2, 0xbf, 0x3f, 0xf1, 0x6f, 0xbb, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x93, 0x87, 0x00, 0x01, 0x24, 0x92, 0x49, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x13, 0x88, 0x00, 0x98, 0x96, 0x80, 0x08, 0x58, 0x3b, 0x00, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0e, 0xaf, 0x00, 0x00, 0x17, 0x70, 0x00, 0x00, 0x00, 0x01, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 10 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, + 0x3f, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x33, 0x33, 0x33, 0x00, 0x1c, 0xfa, 0x77, + 0x0c, 0x6d, 0x39, 0xe6, 0xcb, 0x6f, 0xda, 0xa6, 0x53, 0xcf, 0xd3, 0x97, 0xc4, 0x53, 0x74, 0x46, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xda, 0x74, 0x0e, 0x3f, 0x25, 0x8b, 0xf2, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x1d, 0x4c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 11 */ + 0x20, 0x00, 0x00, 0x00, 0x3e, 0x2b, 0xe2, 0xbf, 0x3e, 0x14, 0x7a, 0xe2, 0x30, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x13, 0x88, 0x00, 0x00, 0x07, 0xd0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x13, 0x88, 0x3c, 0x23, 0xec, 0x84, + 0x20, 0x00, 0x00, 0x00, 0x01, 0xd4, 0x1d, 0x41, 0x01, 0xeb, 0x85, 0x1e, 0x10, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x13, 0x88, 0x00, 0x00, 0x00, 0x00, 0x34, 0x6c, 0xfc, 0xb2, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, + 0x00, 0x00, 0x17, 0x70, 0x00, 0x00, 0x13, 0x88, 0x00, 0x00, 0x23, 0x28, 0x00, 0x00, 0x00, 0x26, + 0x00, 0x00, 0x00, 0x2f, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x09, 0xc4, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x23, 0x01, 0xeb, 0x85, 0x1e, 0x3e, 0x14, 0x7a, 0xe2, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x2d, 0x02, 0x22, 0x22, 0x22, 0x3d, 0xdd, 0xdd, 0xde, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x24, 0xb8, 0x3d, 0xd1, 0xba, 0x8e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 12 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x83, 0xd6, 0x00, 0x00, 0x83, 0xd6, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, 0x21, + 0x00, 0x20, 0x00, 0x00, 0x00, 0x30, 0xfc, 0xf9, 0x40, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x80, 0x00, + 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x0a, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x33, 0x33, 0x33, 0x00, 0x0c, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x31, 0x88, 0x00, 0x07, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf0, 0xde, 0x9a, 0xf8, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0f, 0x90, 0xb2, 0x83, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf7, 0x21, 0x8c, 0xd5, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0c, 0x6f, 0x39, 0x95, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 13 */ + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x53, 0x44, 0x00, 0x00, 0x53, 0x44, 0x00, 0x01, 0x9a, 0x00, 0x00, 0x01, 0x9a, 0x00, 0x00, + 0x00, 0x00, 0x05, 0x46, 0x00, 0x00, 0x05, 0x46, 0x00, 0x00, 0x00, 0x15, 0x00, 0x00, 0x00, 0x19, + 0x00, 0x00, 0x02, 0x58, 0x00, 0x00, 0x02, 0x58, 0x00, 0x00, 0x00, 0x12, 0x00, 0x00, 0x00, 0x03, + 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x96, 0x00, 0x00, 0x01, 0x2c, 0x00, 0x00, 0x00, 0x96, + 0x00, 0xcf, 0x50, 0xa4, 0x00, 0xcf, 0x50, 0xa4, 0x01, 0x35, 0xd0, 0xa4, 0x01, 0x35, 0xd0, 0xa4, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, + 0x00, 0x0c, 0x80, 0x00, 0x00, 0x0c, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x00, + 0x00, 0x0c, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 14 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x01, 0x7b, 0xab, 0x50, 0x01, 0x2d, 0xb6, 0x48, 0x00, 0x00, 0x16, 0xac, 0x00, 0x22, 0x82, 0x60, + 0x00, 0x00, 0x11, 0x8b, 0x04, 0x4c, 0xcc, 0xb0, 0x00, 0x00, 0x00, 0x14, 0x00, 0x00, 0x16, 0x81, + 0x02, 0x78, 0xfe, 0xe0, 0x03, 0x94, 0x3a, 0xb0, 0x00, 0x10, 0xb4, 0x90, 0x00, 0x00, 0x03, 0x2a, + 0x00, 0x00, 0x25, 0xf6, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x10, 0x00, + 0x08, 0x52, 0xdf, 0x89, 0x05, 0x8c, 0x95, 0x06, 0x01, 0x63, 0x25, 0x41, 0x60, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x7b, 0x47, 0x69, 0x02, 0xe5, 0xdb, 0xae, 0x06, 0xf1, 0x85, 0x78, 0x07, 0xdf, 0xab, 0x88, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 15 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xfe, 0x4c, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x08, 0x66, 0x66, 0x66, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x99, 0x99, 0x9a, 0x00, 0x66, 0x66, 0x66, + 0x00, 0x00, 0x01, 0xf4, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x1e, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x66, 0x66, 0x66, 0x00, 0x04, 0xd4, 0x5e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, 0x28, 0x00, 0x00, 0x00, 0x1e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x66, 0x66, 0x66, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x96, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0xf8, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 16 */ + 0xd8, 0xdc, 0xb8, 0xb0, 0xb4, 0xf3, 0xaa, 0xf8, 0xf9, 0xd1, 0xd9, 0x88, 0x9a, 0xf8, 0xf7, 0x3e, + 0xd8, 0xf3, 0x8a, 0x9a, 0xa7, 0x31, 0xd1, 0xd9, 0xf4, 0x10, 0x36, 0xd8, 0xf3, 0x9f, 0x39, 0xf9, + 0xd1, 0xd9, 0xf4, 0x10, 0x36, 0xd8, 0xf3, 0x8f, 0x9f, 0x08, 0x97, 0x60, 0x8a, 0x21, 0xd1, 0xd9, + 0xf4, 0x10, 0x36, 0xda, 0xf1, 0xff, 0xd8, 0xf1, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xba, 0xb2, + 0xb6, 0xa0, 0x80, 0x90, 0x32, 0x18, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xb8, 0xb0, 0xb4, 0xa4, + 0xdf, 0xa5, 0xde, 0xf3, 0xa8, 0xde, 0xd0, 0xdf, 0xa4, 0x84, 0x9f, 0x24, 0xf2, 0xa9, 0xf8, 0xf9, + 0xd1, 0xda, 0xde, 0xa8, 0xde, 0xdf, 0xdf, 0xdf, 0xd8, 0xf4, 0xb1, 0x8d, 0xf3, 0xa8, 0xd0, 0xb0, + 0xb4, 0x8f, 0xf4, 0xb9, 0xaf, 0xd0, 0xc7, 0xbe, 0xbe, 0xb8, 0xae, 0xd0, 0xf3, 0x9f, 0x75, 0xb2, + 0x86, 0xf4, 0xbe, 0xbe, 0xb9, 0xaf, 0xd0, 0xc3, 0xf1, 0xbe, 0xb8, 0xb0, 0xa3, 0xde, 0xdf, 0xdf, + 0xdf, 0xf2, 0xa3, 0x81, 0xc0, 0x80, 0xcd, 0xc7, 0xcf, 0xbc, 0xbd, 0xb4, 0xf1, 0xa3, 0x8d, 0x93, + 0x20, 0xfd, 0x3f, 0x88, 0x6e, 0x76, 0x7e, 0x8d, 0x93, 0xbe, 0xa2, 0x20, 0xfd, 0x31, 0xa0, 0x2c, + 0xfd, 0x32, 0x34, 0xfd, 0x32, 0x3c, 0xfd, 0x32, 0xbe, 0xb9, 0xac, 0x8d, 0x20, 0xb8, 0xbe, 0xbe, + 0xbc, 0xa2, 0x86, 0x9d, 0x08, 0xfd, 0x0f, 0xbc, 0xbc, 0xbc, 0xa3, 0x82, 0x93, 0x01, 0xa9, 0x83, + 0x9e, 0x0e, 0x16, 0x1e, 0xbe, 0xbe, 0xbe, 0xbc, 0xa5, 0x8b, 0x99, 0x2c, 0x54, 0x7c, 0xbc, 0xbc, + 0x85, 0x93, 0xba, 0xa5, 0x2d, 0x55, 0x7d, 0xb8, 0xa5, 0x9d, 0x2c, 0xfd, 0x37, 0x4c, 0xfd, 0x37, + 0x6c, 0xfd, 0x37, 0xf5, 0xa5, 0x85, 0x9f, 0x34, 0x54, 0x74, 0xbd, 0xbd, 0xbd, 0xb1, 0xb6, 0xba, + /* bank # 17 */ + 0x83, 0x95, 0xa5, 0xf1, 0x0e, 0x16, 0x1e, 0xb2, 0xa7, 0x85, 0x95, 0x2a, 0xf0, 0x50, 0x78, 0x87, + 0x93, 0xf1, 0x01, 0xda, 0xa5, 0xdf, 0xdf, 0xdf, 0xd8, 0xa4, 0xdf, 0xdf, 0xdf, 0xb0, 0x80, 0xf2, + 0xa4, 0xc3, 0xcb, 0xc5, 0xf1, 0xb1, 0x8e, 0x94, 0xa4, 0x0e, 0x16, 0x1e, 0xb2, 0x86, 0xbe, 0xa0, + 0x2c, 0x34, 0x3c, 0xbd, 0xbd, 0xb4, 0x96, 0xb8, 0xa1, 0x2c, 0x34, 0x3c, 0xbd, 0xbd, 0xb6, 0x94, + 0xbe, 0xa6, 0x2c, 0xfd, 0x35, 0x34, 0xfd, 0x35, 0x3c, 0xfd, 0x35, 0xbc, 0xb2, 0x8e, 0x94, 0xb8, + 0xbe, 0xbe, 0xa6, 0x2d, 0x55, 0x7d, 0xba, 0xa4, 0x2d, 0x55, 0x7d, 0xb8, 0xb0, 0xb4, 0xa6, 0x8f, + 0x96, 0x2e, 0x36, 0x3e, 0xbc, 0xbc, 0xbc, 0xbd, 0xa6, 0x86, 0x9f, 0xf5, 0x34, 0x54, 0x74, 0xbc, + 0xbe, 0xf1, 0x90, 0xfc, 0xc3, 0x00, 0xd9, 0xf4, 0x11, 0xdf, 0xd8, 0xf3, 0xa0, 0xdf, 0xf1, 0xbc, + 0x86, 0x91, 0xa9, 0x2d, 0x55, 0x7d, 0xbc, 0xbc, 0xbc, 0xa9, 0x80, 0x90, 0xfc, 0x51, 0x00, 0x10, + 0xfc, 0x51, 0x00, 0x10, 0xfc, 0x51, 0x00, 0x10, 0xfc, 0xc1, 0x04, 0xd9, 0xf2, 0xa0, 0xdf, 0xf4, + 0x11, 0xdf, 0xd8, 0xf6, 0xa0, 0xfa, 0x80, 0x90, 0x38, 0xf3, 0xde, 0xda, 0xf8, 0xf4, 0x11, 0xdf, + 0xd8, 0xf1, 0xbd, 0x95, 0xfc, 0xc1, 0x04, 0xd9, 0xbd, 0xbd, 0xbd, 0xf4, 0x11, 0xdf, 0xd8, 0xf6, + 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xbe, 0xb5, 0xa7, 0x84, 0x92, 0x1a, 0xf8, 0xf9, 0xd1, + 0xdb, 0x84, 0x93, 0xf7, 0x6a, 0xb6, 0x87, 0x96, 0xf3, 0x09, 0xff, 0xda, 0xbc, 0xbd, 0xbe, 0xd8, + 0xf1, 0xbc, 0xbc, 0xbc, 0xf6, 0xb0, 0x82, 0xb4, 0x97, 0xb8, 0xa9, 0x02, 0xf7, 0x02, 0xf1, 0xbc, + 0x89, 0x99, 0xa7, 0x04, 0xfd, 0x37, 0xa8, 0xdf, 0x87, 0x98, 0xa7, 0xfc, 0x3d, 0x00, 0x50, 0xf8, + /* bank # 18 */ + 0xf9, 0xd1, 0xd9, 0xa8, 0xdf, 0xf9, 0xd8, 0xf6, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbe, 0xbe, + 0xbe, 0xb7, 0xa7, 0x81, 0x9a, 0x0b, 0xb4, 0x87, 0x9f, 0x1a, 0xf8, 0xf9, 0xd1, 0xbb, 0x81, 0xaa, + 0xc1, 0xd9, 0xf4, 0x12, 0x47, 0xd8, 0xf6, 0xb8, 0xa7, 0x1a, 0xf9, 0xd9, 0xf4, 0x12, 0x47, 0xd8, + 0x8a, 0xf3, 0xbb, 0xaa, 0xc0, 0xc3, 0xb3, 0xaa, 0x8a, 0x9d, 0x1a, 0xfd, 0x1e, 0xb7, 0x9a, 0x08, + 0xb8, 0xb0, 0xb4, 0xa5, 0x85, 0x9d, 0x00, 0xd8, 0xf3, 0xb9, 0xb2, 0xa9, 0x80, 0xcd, 0xf2, 0xc4, + 0xc5, 0xba, 0xf3, 0xa0, 0xd0, 0xde, 0xb1, 0xb4, 0xf7, 0xa7, 0x89, 0x91, 0x72, 0x89, 0x91, 0x47, + 0xb6, 0x97, 0x4a, 0xb9, 0xf2, 0xa9, 0xd0, 0xfa, 0xf9, 0xd1, 0xd9, 0xf4, 0x12, 0x75, 0xd8, 0xf3, + 0xba, 0xa7, 0xf9, 0xdb, 0xfb, 0xd9, 0xf1, 0xb9, 0xb0, 0x81, 0xa9, 0xc3, 0xf2, 0xc5, 0xf3, 0xba, + 0xa0, 0xd0, 0xf8, 0xd8, 0xf1, 0xb1, 0x89, 0xa7, 0xdf, 0xdf, 0xdf, 0xf2, 0xa7, 0xc3, 0xcb, 0xc5, + 0xf1, 0xb2, 0x87, 0xb8, 0xbe, 0xbe, 0xbe, 0xab, 0xc2, 0xc5, 0xc7, 0xbe, 0xb5, 0xb9, 0x97, 0xa5, + 0x22, 0xf0, 0x48, 0x70, 0x3c, 0x98, 0x40, 0x68, 0x34, 0x58, 0x99, 0x60, 0xf1, 0xbc, 0xb3, 0x8e, + 0x95, 0xaa, 0x25, 0x4d, 0x75, 0xbc, 0xbc, 0xbc, 0xb8, 0xb0, 0xb4, 0xa7, 0x88, 0x9f, 0xf7, 0x5a, + 0xf9, 0xda, 0xf3, 0xa8, 0xf8, 0x88, 0x9d, 0xd0, 0x7c, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, 0x52, 0xf9, + 0xda, 0xf3, 0xa8, 0x88, 0x9c, 0xd0, 0xdf, 0x60, 0x68, 0x70, 0x78, 0x9d, 0x60, 0x68, 0x70, 0x78, + 0x9e, 0x70, 0x78, 0x9f, 0x70, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, 0x42, 0xf9, 0xba, 0xa0, 0xd0, 0xf3, + 0xd9, 0xde, 0xd8, 0xf8, 0xf9, 0xd1, 0xb8, 0xda, 0xa8, 0x88, 0x9e, 0xd0, 0x64, 0x68, 0x9f, 0x60, + /* bank # 19 */ + 0xd8, 0xa8, 0x84, 0x98, 0xd0, 0xf7, 0x7e, 0xf1, 0xb2, 0xb6, 0xba, 0x85, 0x91, 0xa7, 0xf4, 0x75, + 0xa8, 0xf4, 0x75, 0xc0, 0xf1, 0x84, 0x91, 0xa7, 0xf4, 0x75, 0xa8, 0xf0, 0xa2, 0x87, 0x0d, 0x20, + 0x59, 0x70, 0x15, 0x38, 0x40, 0x69, 0xa4, 0xf1, 0x62, 0xf0, 0x19, 0x31, 0x48, 0xb8, 0xb1, 0xb4, + 0xf1, 0xa6, 0x80, 0xc6, 0xf4, 0xb0, 0x81, 0xf3, 0xa7, 0xc6, 0xb1, 0x8f, 0x97, 0xf7, 0x02, 0xf9, + 0xda, 0xf4, 0x13, 0x7f, 0xd8, 0xb0, 0xf7, 0xa7, 0x88, 0x9f, 0x52, 0xf9, 0xd9, 0xf4, 0x13, 0x78, + 0xd8, 0xf1, 0xb2, 0xb6, 0xa6, 0x82, 0x92, 0x2a, 0xf0, 0x50, 0xfd, 0x08, 0xf1, 0xa7, 0x84, 0x94, + 0x02, 0xfd, 0x08, 0xb0, 0xb4, 0x86, 0x97, 0x00, 0xb1, 0xba, 0xa7, 0x81, 0x61, 0xd9, 0xf4, 0x13, + 0x97, 0xd8, 0xf1, 0x41, 0xda, 0xf4, 0x13, 0x97, 0xd8, 0xf1, 0xb8, 0xb2, 0xa6, 0x82, 0xc0, 0xd8, + 0xf1, 0xb0, 0xb6, 0x86, 0x92, 0xa7, 0x16, 0xfd, 0x04, 0x0f, 0xfd, 0x04, 0xba, 0x87, 0x91, 0xa7, + 0xf4, 0x75, 0xb6, 0xb2, 0xf4, 0x75, 0xc0, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xbd, 0xbd, 0xbd, 0xb2, + 0xba, 0x84, 0xa7, 0xc3, 0xc5, 0xc7, 0xb2, 0xbc, 0xbc, 0xbc, 0xb6, 0x87, 0x91, 0xaf, 0xf4, 0x75, + 0xa8, 0xa0, 0x8f, 0xf1, 0x0b, 0xf0, 0x20, 0x59, 0x70, 0x15, 0x38, 0x40, 0x69, 0x64, 0x19, 0x31, + 0x48, 0xf1, 0x80, 0x90, 0xaf, 0x6e, 0xfd, 0x04, 0x67, 0xfd, 0x04, 0x8f, 0x91, 0xa7, 0xf4, 0x75, + 0xb6, 0xf4, 0x75, 0xc0, 0xf1, 0xbe, 0xbc, 0xbd, 0xf7, 0xbe, 0xb0, 0xb4, 0xba, 0x88, 0x9e, 0xa3, + 0x6a, 0x9f, 0x66, 0xf0, 0xb1, 0xb5, 0xb9, 0x8a, 0x9a, 0xa2, 0x2c, 0x50, 0x78, 0xb2, 0xb9, 0x8a, + 0xaf, 0xc0, 0xc3, 0xc5, 0xc7, 0x89, 0xad, 0xd0, 0xc4, 0xc7, 0x83, 0xa1, 0xc2, 0xc5, 0xba, 0xbc, + /* bank # 20 */ + 0xbc, 0xbc, 0xb2, 0x81, 0xa2, 0xc0, 0xc3, 0xc5, 0xc7, 0xbc, 0xbc, 0xbd, 0xf4, 0x74, 0x9c, 0xf3, + 0xba, 0xa3, 0xfa, 0xf9, 0xd1, 0xd9, 0xf4, 0x14, 0x33, 0xd8, 0x74, 0xad, 0xbe, 0xbe, 0xbe, 0xba, + 0xb1, 0x82, 0xa3, 0xd0, 0xc7, 0xa9, 0xd0, 0x8d, 0xc4, 0xc7, 0xa3, 0x81, 0xc1, 0xc3, 0xf3, 0xa6, + 0x8d, 0xc2, 0xbe, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xba, 0xb1, 0xaa, 0x8f, 0xc0, 0xc3, 0xc5, 0xc7, + 0xbe, 0xbc, 0xbc, 0xbc, 0xb2, 0xb9, 0x88, 0xaf, 0xc0, 0xc3, 0xc5, 0xc7, 0x80, 0xad, 0xd0, 0xc0, + 0xc3, 0x89, 0xa1, 0xc0, 0xc3, 0xba, 0x81, 0xa2, 0xc0, 0xc3, 0xc5, 0xc7, 0xbc, 0xf4, 0x74, 0x9c, + 0xf3, 0xba, 0xa3, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x14, 0x84, 0xd8, 0x74, 0xad, 0xbe, 0xbe, 0xbe, + 0xb8, 0xb1, 0x82, 0xa7, 0xd0, 0xc7, 0xba, 0xa0, 0x8d, 0xc4, 0xc7, 0xa9, 0x81, 0xc0, 0xc3, 0xf3, + 0xa5, 0x8d, 0xc2, 0xbe, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xba, 0xb1, 0xa8, 0x8f, 0xc0, 0xc3, 0xc5, + 0xc7, 0xbe, 0xf3, 0xba, 0xb2, 0xb6, 0xa3, 0x83, 0x93, 0x08, 0xf9, 0xd9, 0xf4, 0x15, 0x02, 0xd8, + 0xf0, 0xb8, 0xb0, 0xa3, 0x85, 0x94, 0x04, 0x28, 0x50, 0x78, 0xf1, 0xb4, 0x84, 0x93, 0x69, 0xd9, + 0xb6, 0xa5, 0x8d, 0x94, 0x20, 0x2c, 0x34, 0x3c, 0xb4, 0xa4, 0xde, 0xdf, 0xf8, 0xf4, 0x14, 0xcc, + 0xd8, 0xf1, 0xa4, 0xf8, 0xa3, 0x84, 0x94, 0x41, 0xd9, 0xa4, 0xdf, 0xf8, 0xd8, 0xf1, 0x94, 0xfc, + 0xc1, 0x04, 0xd9, 0xa4, 0xfb, 0xa3, 0x86, 0xc0, 0xb1, 0x82, 0x9e, 0x06, 0xfd, 0x1e, 0xa6, 0x81, + 0x96, 0x42, 0x93, 0xf0, 0x68, 0xb0, 0xa3, 0xf1, 0x83, 0x96, 0x01, 0xf5, 0x83, 0x93, 0x00, 0xa6, + 0x86, 0x96, 0xf0, 0x34, 0x83, 0x18, 0xf1, 0xa1, 0x8d, 0x68, 0xa3, 0x81, 0x9b, 0xdb, 0x19, 0x8b, + /* bank # 21 */ + 0xa1, 0xc6, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xd8, 0xf7, 0xb8, + 0xb4, 0xb0, 0xa7, 0x9d, 0x88, 0x72, 0xf9, 0xbc, 0xbd, 0xbe, 0xd9, 0xf4, 0x17, 0xa1, 0xd8, 0xf2, + 0xb8, 0xad, 0xf8, 0xf9, 0xd1, 0xda, 0xde, 0xba, 0xa1, 0xde, 0xae, 0xde, 0xf8, 0xd8, 0xb2, 0x81, + 0xbe, 0xbe, 0xb9, 0xaf, 0xd0, 0xc1, 0xbc, 0xbc, 0xbd, 0xbd, 0xb1, 0xb4, 0xf1, 0xac, 0x8c, 0x92, + 0x0a, 0x18, 0xb5, 0xaf, 0x8c, 0x9d, 0x41, 0xdb, 0x9c, 0x11, 0x8e, 0xad, 0xc0, 0xbe, 0xbe, 0xba, + 0xae, 0xc3, 0xc5, 0xc7, 0x8d, 0xa8, 0xc6, 0xc7, 0xc7, 0xc7, 0xa6, 0xde, 0xdf, 0xdf, 0xdf, 0xa5, + 0xd0, 0xde, 0xdf, 0xbe, 0xbe, 0xd8, 0xb9, 0xac, 0xdf, 0xaf, 0x8d, 0x9c, 0x11, 0xd9, 0x8c, 0xc5, + 0xda, 0xc1, 0xd8, 0xaf, 0x8f, 0x21, 0xf5, 0x9f, 0x00, 0xf1, 0x8c, 0x9c, 0x45, 0xd9, 0x8f, 0xac, + 0xc1, 0xd8, 0xf2, 0xaf, 0xdf, 0xf8, 0xf8, 0xdf, 0xf8, 0xf8, 0xf8, 0xaf, 0x8f, 0x9f, 0x59, 0xd1, + 0xdb, 0xf1, 0x8c, 0x9c, 0x31, 0xf2, 0x8f, 0xaf, 0xd0, 0xc3, 0xd8, 0xaf, 0x8f, 0x9f, 0x39, 0xd1, + 0xdb, 0xf1, 0x8c, 0x9c, 0x69, 0xf2, 0x8f, 0xaf, 0xd0, 0xc5, 0xd8, 0x8f, 0xbe, 0xbe, 0xba, 0xa1, + 0xc6, 0xbc, 0xbc, 0xbd, 0xbd, 0xf2, 0xb1, 0xb5, 0xb9, 0xae, 0xf9, 0xda, 0xf4, 0x17, 0x74, 0xd8, + 0xf2, 0x8e, 0xc2, 0xf1, 0xb2, 0x80, 0x9a, 0xf5, 0xaf, 0x24, 0xd9, 0xf4, 0x17, 0x74, 0xd8, 0xf5, + 0x44, 0xd9, 0xf4, 0x17, 0x74, 0xd8, 0xf5, 0x64, 0xd9, 0xf4, 0x17, 0x74, 0xd8, 0xf1, 0xb1, 0xb6, + 0x8b, 0x90, 0xaf, 0x2d, 0x55, 0x7d, 0xb5, 0x8c, 0x9f, 0xad, 0x0e, 0x16, 0x1e, 0x8b, 0x9d, 0xab, + 0x2c, 0x54, 0x7c, 0x8d, 0x9f, 0xaa, 0x2e, 0x56, 0x7e, 0x8a, 0x9c, 0xaa, 0x2c, 0x54, 0x7c, 0x9b, + /* bank # 22 */ + 0xac, 0x26, 0x46, 0x66, 0xaf, 0x8d, 0x9d, 0x00, 0x9c, 0x0d, 0xdb, 0x11, 0x8f, 0x19, 0xf4, 0x16, + 0x14, 0xd8, 0x17, 0x74, 0xd8, 0xf1, 0xb2, 0x81, 0xb6, 0x90, 0xaf, 0x2d, 0x55, 0x7d, 0xb1, 0x8f, + 0xb5, 0x9f, 0xaf, 0xf5, 0x2c, 0x54, 0x7c, 0xf1, 0xb2, 0x8c, 0x9f, 0xad, 0x6d, 0xdb, 0x71, 0x79, + 0xf4, 0x16, 0x42, 0xd8, 0xf3, 0xba, 0xa1, 0xde, 0xf8, 0xf1, 0x80, 0xa1, 0xc3, 0xc5, 0xc7, 0xf4, + 0x16, 0x51, 0xd8, 0xf3, 0xb6, 0xba, 0x91, 0xfc, 0xc0, 0x28, 0xda, 0xa1, 0xf8, 0xd9, 0xf4, 0x17, + 0x74, 0xd8, 0xf3, 0xb9, 0xae, 0xf8, 0xf9, 0xd1, 0xd9, 0xf8, 0xf4, 0x17, 0x74, 0xd8, 0xf1, 0xba, + 0xb1, 0xb5, 0xa0, 0x8b, 0x93, 0x3e, 0x5e, 0x7e, 0xab, 0x83, 0xc0, 0xc5, 0xb2, 0xb6, 0xa3, 0x87, + 0xc0, 0xc3, 0xc5, 0xc7, 0xa2, 0x88, 0xc0, 0xc3, 0xc5, 0xc7, 0xa4, 0x86, 0xc0, 0xc3, 0xc5, 0xc7, + 0xa5, 0x85, 0xc4, 0xc7, 0xac, 0x8d, 0xc0, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xb9, 0xb1, 0xb5, + 0xad, 0xd0, 0xde, 0xaf, 0x8c, 0x9c, 0x41, 0xd9, 0xf4, 0x16, 0xc0, 0xd8, 0xf1, 0xf8, 0xf9, 0xd1, + 0xd9, 0xf4, 0x16, 0xd9, 0xd8, 0xf1, 0xaf, 0x8d, 0x9c, 0x31, 0xda, 0x8c, 0xc5, 0xd9, 0xc3, 0xd8, + 0xaf, 0x8f, 0x21, 0xf5, 0x9f, 0x00, 0xf1, 0xad, 0xd0, 0xb0, 0x82, 0x9f, 0x02, 0xf4, 0x16, 0xd9, + 0xd8, 0xf1, 0xaf, 0x8d, 0x9c, 0x31, 0xd9, 0x8c, 0xc5, 0xda, 0xc3, 0xd8, 0xaf, 0x8f, 0x21, 0xf5, + 0x9f, 0x00, 0xf1, 0xad, 0xd0, 0xb0, 0x83, 0x9f, 0x02, 0xd8, 0xf1, 0xb1, 0x8c, 0xad, 0xc1, 0xbe, + 0xbe, 0xbd, 0xbd, 0xba, 0xb6, 0xac, 0x8d, 0x9c, 0x40, 0xbc, 0xbc, 0xb2, 0xa0, 0xde, 0xf8, 0xf8, + 0xf8, 0xf8, 0xf8, 0xfd, 0x0f, 0xf5, 0xaf, 0x88, 0x98, 0x00, 0x2c, 0x54, 0x7c, 0xf1, 0xaf, 0x80, + /* bank # 23 */ + 0x9f, 0x01, 0xdb, 0x09, 0x11, 0x19, 0xf4, 0x17, 0x13, 0xd8, 0xf2, 0xa1, 0xf8, 0xf9, 0xd1, 0xda, + 0xf1, 0xac, 0xde, 0xd8, 0xf3, 0xae, 0xde, 0xf8, 0xf4, 0x1a, 0x8e, 0xd8, 0xf1, 0xa7, 0x83, 0xc0, + 0xc3, 0xc5, 0xc7, 0xa8, 0x82, 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x84, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, + 0x85, 0xd0, 0xc0, 0xc3, 0x8d, 0x9d, 0xaf, 0x39, 0xd9, 0xf4, 0x17, 0x74, 0xd8, 0xf1, 0x83, 0xb5, + 0x9e, 0xae, 0x34, 0xfd, 0x0a, 0x54, 0xfd, 0x0a, 0x74, 0xfd, 0x0a, 0xf2, 0xa1, 0xde, 0xf8, 0xf8, + 0xf8, 0xf1, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xb9, 0xb1, 0xb5, 0x8c, 0xad, 0xc0, 0xaf, 0x9c, + 0x11, 0xd9, 0xae, 0xc0, 0xbc, 0xbc, 0xb2, 0x8e, 0xc3, 0xc5, 0xc7, 0xbc, 0xbc, 0xd8, 0xbe, 0xbe, + 0xbc, 0xbc, 0xbd, 0xbd, 0xd8, 0xf2, 0xba, 0xb2, 0xb5, 0xaf, 0x81, 0x97, 0x01, 0xd1, 0xb9, 0xa7, + 0xc0, 0xda, 0xf4, 0x17, 0x8c, 0xd8, 0xf2, 0xba, 0xae, 0xf8, 0xf9, 0xd1, 0xda, 0xf3, 0xbe, 0xbe, + 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xb8, 0xb0, 0xb4, 0xa5, 0x85, 0x9c, 0x08, 0xbe, 0xbc, + 0xbd, 0xd8, 0xf7, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbb, 0xb4, 0xb0, 0xaf, 0x9e, 0x88, 0x62, + 0xf9, 0xbc, 0xbd, 0xd9, 0xf4, 0x19, 0xe7, 0xd8, 0xf1, 0xbc, 0xbc, 0xbc, 0xb1, 0x85, 0xba, 0xb5, + 0xa0, 0x98, 0x06, 0x26, 0x46, 0xbc, 0xb9, 0xb3, 0xb6, 0xf1, 0xaf, 0x81, 0x90, 0x2d, 0x55, 0x7d, + 0xb1, 0xb5, 0xaf, 0x8f, 0x9f, 0xf5, 0x2c, 0x54, 0x7c, 0xf1, 0xbb, 0xaf, 0x86, 0x9f, 0x69, 0xdb, + 0x71, 0x79, 0xda, 0xf3, 0xa0, 0xdf, 0xf8, 0xf1, 0xa1, 0xde, 0xf2, 0xf8, 0xd8, 0xb3, 0xb7, 0xf1, + 0x8c, 0x9b, 0xaf, 0x19, 0xd9, 0xac, 0xde, 0xf3, 0xa0, 0xdf, 0xf8, 0xd8, 0xaf, 0x80, 0x90, 0x69, + /* bank # 24 */ + 0xd9, 0xa0, 0xfa, 0xf1, 0xb2, 0x80, 0xa1, 0xc3, 0xc5, 0xc7, 0xf2, 0xa0, 0xd0, 0xdf, 0xf8, 0xf4, + 0x19, 0xd1, 0xd8, 0xf2, 0xa0, 0xd0, 0xdf, 0xf1, 0xbc, 0xbc, 0xbc, 0xb1, 0xad, 0x8a, 0x9e, 0x26, + 0x46, 0x66, 0xbc, 0xb3, 0xf3, 0xa2, 0xde, 0xf8, 0xf4, 0x1a, 0x17, 0xd8, 0xf1, 0xaa, 0x8d, 0xc1, + 0xf2, 0xa1, 0xf8, 0xf9, 0xd1, 0xda, 0xf4, 0x18, 0x5c, 0xd8, 0xf1, 0xaf, 0x8a, 0x9a, 0x21, 0x8f, + 0x90, 0xf5, 0x10, 0xda, 0xf4, 0x18, 0x5c, 0xd8, 0xf1, 0x91, 0xfc, 0xc0, 0x04, 0xd9, 0xf4, 0x18, + 0xa3, 0xd8, 0xf3, 0xa1, 0xde, 0xf8, 0xa0, 0xdf, 0xf8, 0xf4, 0x19, 0xd1, 0xf3, 0x91, 0xfc, 0xc0, + 0x07, 0xd9, 0xf4, 0x18, 0xa3, 0xd8, 0xf1, 0xaf, 0xb1, 0x84, 0x9c, 0x01, 0xb3, 0xb5, 0x80, 0x97, + 0xdb, 0xf3, 0x21, 0xb9, 0xa7, 0xd9, 0xf8, 0xf4, 0x18, 0xa3, 0xd8, 0xf3, 0xb9, 0xa7, 0xde, 0xf8, + 0xbb, 0xf1, 0xa3, 0x87, 0xc0, 0xc3, 0xc5, 0xc7, 0xa4, 0x88, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, 0x89, + 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x86, 0xc4, 0xc7, 0xa1, 0x82, 0xc3, 0xc5, 0xc7, 0xf3, 0xa1, 0xde, + 0xf4, 0x19, 0xe7, 0xd8, 0xf1, 0xbb, 0xb3, 0xb7, 0xa1, 0xf8, 0xf9, 0xd1, 0xda, 0xf2, 0xa0, 0xd0, + 0xdf, 0xf8, 0xd8, 0xf1, 0xb9, 0xb1, 0xb6, 0xa8, 0x87, 0x90, 0x2d, 0x55, 0x7d, 0xf5, 0xb5, 0xa8, + 0x88, 0x98, 0x2c, 0x54, 0x7c, 0xf1, 0xaf, 0x86, 0x98, 0x29, 0xdb, 0x31, 0x39, 0xf4, 0x19, 0xe7, + 0xd8, 0xf1, 0xb3, 0xb6, 0xa7, 0x8a, 0x90, 0x4c, 0x54, 0x5c, 0xba, 0xa0, 0x81, 0x90, 0x2d, 0x55, + 0x7d, 0xbb, 0xf2, 0xa2, 0xf8, 0xf9, 0xd1, 0xda, 0xde, 0xf4, 0x19, 0xe7, 0xd8, 0xf1, 0xba, 0xb0, + 0xab, 0x8f, 0xc0, 0xc7, 0xb3, 0xa3, 0x83, 0xc0, 0xc3, 0xc5, 0xc7, 0xa2, 0x84, 0xc0, 0xc3, 0xc5, + /* bank # 25 */ + 0xc7, 0xa4, 0x85, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, 0x86, 0xc0, 0xc3, 0xac, 0x8c, 0xc2, 0xf3, 0xae, + 0xde, 0xf8, 0xf8, 0xf4, 0x1a, 0x8e, 0xd8, 0xf1, 0xb2, 0xbb, 0xa3, 0x83, 0xc0, 0xc3, 0xc5, 0xc7, + 0xa4, 0x82, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, 0x84, 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x85, 0xc0, 0xc3, + 0xac, 0x8c, 0xc4, 0xb3, 0xb7, 0xaf, 0x85, 0x95, 0x56, 0xfd, 0x0f, 0x86, 0x96, 0x06, 0xfd, 0x0f, + 0xf0, 0x84, 0x9f, 0xaf, 0x4c, 0x70, 0xfd, 0x0f, 0xf1, 0x86, 0x96, 0x2e, 0xfd, 0x0f, 0x84, 0x9f, + 0x72, 0xfd, 0x0f, 0xdf, 0xaf, 0x2c, 0x54, 0x7c, 0xaf, 0x8c, 0x69, 0xdb, 0x71, 0x79, 0x8b, 0x9c, + 0x61, 0xf4, 0x19, 0x67, 0xda, 0x19, 0xe7, 0xd8, 0xf1, 0xab, 0x83, 0x91, 0x28, 0xfd, 0x05, 0x54, + 0xfd, 0x05, 0x7c, 0xfd, 0x05, 0xb8, 0xbd, 0xbd, 0xbd, 0xb5, 0xa3, 0x8b, 0x95, 0x05, 0x2d, 0x55, + 0xbd, 0xb4, 0xbb, 0xad, 0x8e, 0x93, 0x0e, 0x16, 0x1e, 0xb7, 0xf3, 0xa2, 0xde, 0xf8, 0xf8, 0xf4, + 0x1a, 0x17, 0xd8, 0xf2, 0xa1, 0xf8, 0xf9, 0xd1, 0xd9, 0xf1, 0xaf, 0x8d, 0x9a, 0x01, 0xf5, 0x8f, + 0x90, 0xdb, 0x00, 0xf4, 0x19, 0xe7, 0xda, 0xf1, 0xaa, 0x8d, 0xc0, 0xae, 0x8b, 0xc1, 0xc3, 0xc5, + 0xa1, 0xde, 0xa7, 0x83, 0xc0, 0xc3, 0xc5, 0xc7, 0xa8, 0x84, 0xc0, 0xc3, 0xc5, 0xc7, 0xa9, 0x85, + 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x86, 0xd0, 0xc0, 0xc3, 0xa2, 0x81, 0xc3, 0xc5, 0xc7, 0xf4, 0x19, + 0xe7, 0xf1, 0xbb, 0xb3, 0xa3, 0xde, 0xdf, 0xdf, 0xdf, 0xa4, 0x8c, 0xc4, 0xc5, 0xc5, 0xc5, 0xa5, + 0xde, 0xdf, 0xdf, 0xdf, 0xa6, 0xde, 0xdf, 0xd8, 0xf3, 0xb9, 0xae, 0xdf, 0xba, 0xae, 0xde, 0xbb, + 0xa2, 0xde, 0xbe, 0xbc, 0xb3, 0xbd, 0xb7, 0xaf, 0x8e, 0x9c, 0x01, 0xd1, 0xac, 0xc0, 0xd9, 0xae, + /* bank # 26 */ + 0xde, 0xd8, 0xf1, 0xb1, 0x83, 0xb9, 0xa7, 0xd0, 0xc4, 0xb8, 0xae, 0xde, 0xbe, 0xbe, 0xbe, 0xbb, + 0xbc, 0xbc, 0xbc, 0xb3, 0xbd, 0xbd, 0xbd, 0xd8, 0xf3, 0xa2, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x1a, + 0x8c, 0xd8, 0xf5, 0xad, 0x8d, 0x9d, 0x2c, 0x54, 0x7c, 0xf1, 0xaf, 0x49, 0xda, 0xc3, 0xc5, 0xd9, + 0xc5, 0xc3, 0xd8, 0xaf, 0x9f, 0x69, 0xd0, 0xda, 0xc7, 0xd9, 0x8f, 0xc3, 0x8d, 0xaf, 0xc7, 0xd8, + 0xb9, 0xa9, 0x8f, 0x9f, 0xf0, 0x54, 0x78, 0xf1, 0xfd, 0x0f, 0xa6, 0xb1, 0x89, 0xc2, 0xb3, 0xaf, + 0x8f, 0x9f, 0x2e, 0xfd, 0x11, 0xb1, 0xb5, 0xa9, 0x89, 0x9f, 0x2c, 0xf3, 0xae, 0xdf, 0xf8, 0xf8, + 0xf4, 0x1c, 0x43, 0xd8, 0xf1, 0xad, 0x86, 0x99, 0x06, 0xfd, 0x10, 0xdf, 0xf8, 0xfd, 0x0f, 0xad, + 0x8d, 0x9d, 0x4c, 0xbb, 0xb3, 0xad, 0x8f, 0x9d, 0x2a, 0xfd, 0x0f, 0xb7, 0x92, 0xfc, 0xc0, 0x04, + 0xd9, 0xf4, 0x18, 0x2b, 0xd8, 0xfc, 0xc0, 0x08, 0xd9, 0xf4, 0x19, 0x92, 0xd8, 0xf1, 0xd8, 0xf3, + 0xba, 0xb2, 0xb6, 0xae, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x1c, 0x41, 0xd8, 0xf1, 0xaf, 0xde, 0xf9, + 0xfd, 0x0f, 0x80, 0x90, 0x2c, 0x54, 0x7c, 0xa0, 0x2a, 0xf0, 0x50, 0x78, 0xfd, 0x0f, 0xf1, 0xa2, + 0x82, 0x9c, 0x00, 0x24, 0x44, 0x64, 0xa9, 0x8f, 0x94, 0xf0, 0x04, 0xfd, 0x0f, 0x0c, 0x30, 0xfd, + 0x0f, 0x1c, 0x95, 0x20, 0x48, 0xfd, 0x0f, 0xf1, 0x99, 0xc1, 0x2c, 0x54, 0x7c, 0xaa, 0x82, 0x99, + 0x02, 0xfd, 0x0f, 0x2e, 0xfd, 0x0f, 0x56, 0xfd, 0x0f, 0x7e, 0xfd, 0x0f, 0xac, 0x83, 0x9f, 0xf0, + 0x04, 0x28, 0x50, 0x78, 0xfd, 0x0f, 0x8c, 0x90, 0xf1, 0x21, 0xf5, 0x8c, 0x9c, 0x2c, 0xf1, 0xaf, + 0xde, 0xf1, 0x89, 0xaf, 0x9f, 0xfc, 0xc0, 0x00, 0xd9, 0xc1, 0x8a, 0xc1, 0x82, 0xc1, 0xd8, 0xfc, + /* bank # 27 */ + 0xc0, 0x04, 0xd9, 0xc3, 0x8a, 0xc3, 0x82, 0xc3, 0xd8, 0xfc, 0xc0, 0x08, 0xd9, 0xc5, 0x8a, 0xc5, + 0x82, 0xc5, 0xd8, 0xfc, 0xc0, 0x0c, 0xd9, 0xc7, 0x8a, 0xc7, 0x82, 0xc7, 0xd8, 0xfc, 0xc0, 0x10, + 0xd9, 0xf4, 0x1b, 0xfb, 0xd8, 0xf1, 0x8b, 0xab, 0xd0, 0xc0, 0x9f, 0x2e, 0xfd, 0x0f, 0xa0, 0xde, + 0xab, 0xd0, 0x90, 0x65, 0xa0, 0x8f, 0x9f, 0x4a, 0xfd, 0x0f, 0xab, 0x8b, 0x90, 0x00, 0xb9, 0xa9, + 0xc1, 0xf3, 0xae, 0xdf, 0xf8, 0xf4, 0x1c, 0x43, 0xd8, 0xf1, 0xba, 0xb1, 0xb6, 0x89, 0xab, 0xc1, + 0xb2, 0xaf, 0xd0, 0x8b, 0x9f, 0x3e, 0xfd, 0x0f, 0x5a, 0xfd, 0x0f, 0x9f, 0xfc, 0xc0, 0x00, 0xd9, + 0xf1, 0x8f, 0xa2, 0xc6, 0xd8, 0xfc, 0xc0, 0x04, 0xd9, 0x8f, 0xa2, 0xc7, 0x84, 0xab, 0xd0, 0xc0, + 0xaf, 0x8a, 0x9b, 0x1e, 0xfd, 0x0f, 0x36, 0xfd, 0x0f, 0xa4, 0x8f, 0x30, 0xaa, 0x9a, 0x40, 0xd8, + 0x9f, 0xfc, 0xc0, 0x08, 0xd9, 0x8f, 0xa2, 0xd0, 0xc6, 0x84, 0xab, 0xd0, 0xc2, 0xaf, 0x8a, 0x9b, + 0x1e, 0xfd, 0x0f, 0x56, 0xfd, 0x0f, 0xa4, 0x8f, 0x34, 0xaa, 0x9a, 0x40, 0x84, 0xab, 0xd0, 0xc4, + 0xaf, 0x8a, 0x9b, 0x3e, 0xfd, 0x0f, 0x56, 0xfd, 0x0f, 0xa4, 0xd0, 0x8f, 0x30, 0xaa, 0x9a, 0x4c, + 0xd8, 0x9f, 0xfc, 0xc0, 0x0c, 0xd9, 0x8f, 0xa2, 0xd0, 0xc7, 0x84, 0xab, 0xd0, 0xc6, 0xaf, 0x8a, + 0x9b, 0x1e, 0xfd, 0x0f, 0x76, 0xfd, 0x0f, 0xa4, 0xd0, 0x8f, 0x34, 0xaa, 0x9a, 0x40, 0x85, 0xab, + 0xd0, 0xc0, 0xaf, 0x8a, 0x9b, 0x3e, 0xfd, 0x0f, 0x76, 0xfd, 0x0f, 0xa5, 0x8f, 0x30, 0xaa, 0x9a, + 0x4c, 0x85, 0xab, 0xd0, 0xc2, 0xaf, 0x8a, 0x9b, 0x5e, 0xfd, 0x0f, 0x76, 0xfd, 0x0f, 0xa5, 0x8f, + 0x34, 0xaa, 0xd0, 0x9a, 0x50, 0xd8, 0xaf, 0xf8, 0xf4, 0x1a, 0xf1, 0xf1, 0xd8, 0x8b, 0x9c, 0xaf, + /* bank # 28 */ + 0x2a, 0xfd, 0x0f, 0x8a, 0x9f, 0xb9, 0xaf, 0x02, 0xfd, 0x0f, 0x26, 0xfd, 0x0f, 0x46, 0xfd, 0x0f, + 0x66, 0xfd, 0x0f, 0x83, 0xb5, 0x9f, 0xba, 0xa3, 0x00, 0x2c, 0x54, 0x7c, 0xb6, 0x82, 0x92, 0xa0, + 0x31, 0xd9, 0xad, 0xc3, 0xda, 0xad, 0xc5, 0xd8, 0x8d, 0xa0, 0x39, 0xda, 0x82, 0xad, 0xc7, 0xd8, + 0xf3, 0x9e, 0xfc, 0xc0, 0x04, 0xd9, 0xf4, 0x17, 0x1b, 0xd8, 0xfc, 0xc0, 0x08, 0xd9, 0xf4, 0x19, + 0x16, 0xd8, 0xf1, 0xd8, 0xf1, 0xb9, 0xb1, 0xb5, 0xa9, 0xde, 0xf8, 0x89, 0x99, 0xaf, 0x31, 0xd9, + 0xf4, 0x1c, 0x97, 0xd8, 0xf1, 0x85, 0xaf, 0x29, 0xd9, 0x84, 0xa9, 0xc2, 0xd8, 0x85, 0xaf, 0x49, + 0xd9, 0x84, 0xa9, 0xc4, 0xd8, 0x85, 0xaf, 0x69, 0xd9, 0x84, 0xa9, 0xc6, 0xd8, 0x89, 0xaf, 0x39, + 0xda, 0x8e, 0xa9, 0x50, 0xf4, 0x1c, 0x97, 0xd8, 0xf1, 0x89, 0xaa, 0x7c, 0xfd, 0x02, 0x9a, 0x68, + 0xd8, 0xf1, 0xaa, 0xfb, 0xda, 0x89, 0x99, 0xaf, 0x26, 0xfd, 0x0f, 0x8f, 0x95, 0x25, 0x89, 0x9f, + 0xa9, 0x12, 0xfd, 0x0f, 0xf4, 0x1c, 0x80, 0xd8, 0xf3, 0x9e, 0xfc, 0xc1, 0x04, 0xd9, 0xf4, 0x1b, + 0x48, 0xd8, 0xfc, 0xc1, 0x08, 0xd9, 0xf4, 0x1a, 0x63, 0xd8, 0xf1, 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, + 0xf3, 0xb8, 0xb4, 0xb0, 0x8f, 0xa8, 0xc0, 0xf9, 0xac, 0x84, 0x97, 0xf5, 0x1a, 0xf1, 0xf8, 0xf9, + 0xd1, 0xda, 0xa8, 0xde, 0xd8, 0x95, 0xfc, 0xc1, 0x03, 0xd9, 0xa8, 0xde, 0xd8, 0xbc, 0xbc, 0xf1, + 0x98, 0xfc, 0xc0, 0x1c, 0xdb, 0x95, 0xfc, 0xc0, 0x03, 0xa5, 0xde, 0xa4, 0xde, 0xd8, 0xac, 0x88, + 0x95, 0x00, 0xd1, 0xd9, 0xa5, 0xf8, 0xd8, 0xa4, 0xfc, 0x80, 0x04, 0x88, 0x95, 0xa4, 0xfc, 0x08, + 0x04, 0x20, 0xf7, 0xbc, 0xbc, 0xbd, 0xbd, 0xb5, 0xac, 0x84, 0x9f, 0xf6, 0x02, 0xf8, 0xf9, 0xd1, + /* bank # 29 */ + 0xdb, 0x84, 0x93, 0xf7, 0x6a, 0xf9, 0xd9, 0xf3, 0xbc, 0xbc, 0xa8, 0x88, 0x92, 0x18, 0xbc, 0xbc, + 0xd8, 0xbc, 0xbc, 0xb4, 0xa8, 0x88, 0x9e, 0x08, 0xf4, 0xbe, 0xbe, 0xa1, 0xd0, 0xbc, 0xbc, 0xf7, + 0xbe, 0xbe, 0xb5, 0xac, 0x84, 0x93, 0x6a, 0xf9, 0xbd, 0xbd, 0xb4, 0xd9, 0xf2, 0xac, 0x8c, 0x97, + 0x18, 0xf6, 0x84, 0x9c, 0x02, 0xf8, 0xf9, 0xdb, 0xd1, 0xf1, 0xa5, 0xdf, 0xd8, 0xf7, 0xbe, 0xbe, + 0xbd, 0xbd, 0xa7, 0x9d, 0x88, 0x7a, 0xf9, 0xd9, 0xf4, 0x1e, 0xe1, 0xd8, 0xf1, 0xbe, 0xbe, 0xac, + 0xde, 0xdf, 0xac, 0x88, 0x9f, 0xf7, 0x5a, 0x56, 0xf1, 0xbc, 0xbc, 0xbd, 0xbd, 0x95, 0xfc, 0xc0, + 0x07, 0xda, 0xf4, 0x1e, 0x7c, 0xd8, 0xf1, 0xfc, 0xc0, 0x00, 0xdb, 0x9c, 0xfc, 0xc1, 0x00, 0xf4, + 0x1e, 0xa1, 0xd8, 0xf1, 0xac, 0x95, 0xfc, 0xc0, 0x08, 0xda, 0xf4, 0x1d, 0xbe, 0xd8, 0xf1, 0x82, + 0x90, 0x79, 0x2d, 0x55, 0xf5, 0x8c, 0x9c, 0x04, 0xac, 0x2c, 0x54, 0xf1, 0xbc, 0xbc, 0xbc, 0x80, + 0x5d, 0xdb, 0x49, 0x51, 0xf4, 0xbc, 0x1d, 0x9c, 0xda, 0xbc, 0x1e, 0x78, 0xd8, 0xf5, 0x86, 0x98, + 0x38, 0xd9, 0xf1, 0x82, 0x90, 0x2d, 0xd8, 0xac, 0xd0, 0x86, 0x98, 0xf5, 0x5c, 0xd9, 0xf1, 0x82, + 0x90, 0x55, 0xd8, 0xac, 0x8c, 0x9c, 0x00, 0x00, 0xa5, 0xdf, 0xf8, 0xf4, 0x1d, 0xc9, 0xd8, 0xf1, + 0x82, 0x96, 0x2d, 0x55, 0x7d, 0x8c, 0x9c, 0x34, 0x18, 0xf1, 0xac, 0x95, 0xf5, 0x1c, 0xd9, 0xf4, + 0x1e, 0x78, 0xd8, 0xf1, 0xac, 0x83, 0x90, 0x45, 0xd9, 0xa0, 0xf8, 0xac, 0x8c, 0x9c, 0x06, 0xd2, + 0xa1, 0x91, 0x00, 0x2c, 0x81, 0xd6, 0xf0, 0xa1, 0xd0, 0x8c, 0x9c, 0x28, 0xd3, 0x87, 0xd4, 0xa7, + 0x8c, 0x20, 0xd3, 0xf1, 0xa4, 0x84, 0x90, 0x2c, 0x54, 0x7c, 0xd8, 0xac, 0x83, 0x90, 0x45, 0xd9, + /* bank # 30 */ + 0xf4, 0x1e, 0xa1, 0xd8, 0xf1, 0xac, 0x81, 0x91, 0x02, 0xfd, 0x14, 0x85, 0x66, 0xfd, 0x1d, 0x88, + 0x4e, 0xfd, 0x1b, 0x87, 0xd4, 0xfd, 0x54, 0xad, 0x8d, 0x4e, 0xf0, 0x81, 0x9c, 0xab, 0xd6, 0xfd, + 0x06, 0x8d, 0x31, 0x8c, 0x10, 0x10, 0x01, 0x01, 0x01, 0x39, 0xac, 0x8b, 0x98, 0xf5, 0x08, 0xd9, + 0xf4, 0x1e, 0x78, 0xd8, 0xf1, 0xa9, 0x82, 0x96, 0x01, 0x95, 0xfc, 0xc1, 0x00, 0xda, 0xf4, 0x1e, + 0x50, 0xdb, 0xf1, 0xac, 0x89, 0x93, 0xf5, 0x18, 0xf1, 0xa5, 0xdf, 0xf8, 0xd8, 0xf4, 0x1e, 0x7c, + 0xd8, 0xf1, 0xa4, 0x84, 0x95, 0x34, 0xfd, 0x05, 0x54, 0xfd, 0x05, 0x74, 0xfd, 0x05, 0xa9, 0x94, + 0xf5, 0x2c, 0x54, 0x7c, 0xf1, 0xac, 0x87, 0x99, 0x49, 0xdb, 0x51, 0x59, 0x84, 0xab, 0xc3, 0xc5, + 0xc7, 0x82, 0xa6, 0xc0, 0xf3, 0xaa, 0xdf, 0xf8, 0xd8, 0xf1, 0xa5, 0xdf, 0xd8, 0xf1, 0xa0, 0xde, + 0xa1, 0xde, 0xdf, 0xdf, 0xdf, 0xa7, 0xde, 0xdf, 0xa4, 0xdf, 0xdf, 0xdf, 0xa2, 0x95, 0xfc, 0xc0, + 0x01, 0xd9, 0x80, 0xc3, 0xc5, 0xc7, 0xa8, 0x83, 0xc1, 0xda, 0x86, 0xc3, 0xc5, 0xc7, 0xa8, 0x83, + 0xc3, 0xd8, 0xf1, 0x9a, 0xfc, 0xc1, 0x04, 0xd9, 0xac, 0x82, 0x96, 0x01, 0xf3, 0xaa, 0xde, 0xf8, + 0xf8, 0xf8, 0xdb, 0xf5, 0xac, 0x8c, 0x9a, 0x18, 0xf3, 0xaa, 0xf9, 0xd8, 0xac, 0x8a, 0x9a, 0x41, + 0xd1, 0xaa, 0xd0, 0xc0, 0xd9, 0xf2, 0xac, 0x85, 0x9a, 0x41, 0xdb, 0xd1, 0xbc, 0xbc, 0xbd, 0xbd, + 0xbe, 0xbe, 0xf4, 0x1e, 0xe1, 0xd8, 0xf3, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xa5, 0x85, 0x9c, + 0x10, 0xd8, 0xf1, 0xb8, 0xb0, 0xb4, 0xa7, 0x88, 0x9e, 0xf7, 0x7a, 0xf9, 0xd9, 0xf4, 0x20, 0x18, + 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xbb, 0xa2, 0xf9, 0xda, 0xbe, 0xf4, 0x20, 0x18, 0xd8, 0xf1, 0xbc, + /* bank # 31 */ + 0xbc, 0xbc, 0xb3, 0x80, 0xc6, 0xaf, 0xde, 0xd0, 0xdf, 0xbc, 0xb2, 0x84, 0xbd, 0xbd, 0xbd, 0xb7, + 0x9f, 0xa0, 0x60, 0xbc, 0xbc, 0xbc, 0xb3, 0x85, 0x90, 0xaf, 0x01, 0x9f, 0x46, 0x8f, 0xa2, 0x0e, + 0x85, 0x92, 0xaf, 0xd0, 0x29, 0x9f, 0x52, 0xa5, 0x08, 0x34, 0xa0, 0xfb, 0x86, 0x95, 0xaf, 0x29, + 0xda, 0xa6, 0xde, 0xf4, 0x1f, 0x4c, 0xd8, 0xf1, 0xa0, 0xfa, 0xf9, 0xda, 0xa6, 0xde, 0xf4, 0x1f, + 0x4c, 0xd8, 0xf1, 0xa6, 0xf8, 0x96, 0xaf, 0x19, 0xd9, 0xa3, 0xde, 0xf8, 0xd8, 0xf1, 0x85, 0x94, + 0xaf, 0x31, 0xd9, 0xa3, 0xde, 0xf8, 0xf8, 0x80, 0xa0, 0xc5, 0xd8, 0x85, 0x96, 0xaf, 0x31, 0xd9, + 0xa3, 0xde, 0xf8, 0xf8, 0xf8, 0x80, 0xa5, 0xc0, 0x86, 0xc3, 0xd8, 0xa8, 0xdf, 0xa1, 0xde, 0x85, + 0x91, 0xaf, 0x0c, 0x0d, 0xf5, 0x8f, 0x9f, 0xaf, 0x2c, 0x54, 0xf1, 0x97, 0xfc, 0xc0, 0x04, 0xdb, + 0x8f, 0xaf, 0x51, 0xa8, 0xdf, 0xf8, 0xd8, 0x98, 0xfc, 0xc0, 0x08, 0xd9, 0xf4, 0x1f, 0xb4, 0xd8, + 0xf1, 0xfc, 0xc0, 0x0c, 0xd9, 0xf4, 0x1f, 0xdd, 0xd8, 0xf1, 0x93, 0xfc, 0xc0, 0x09, 0xd9, 0xa4, + 0xde, 0xa8, 0xde, 0xf8, 0xf8, 0xd8, 0xfc, 0xc0, 0x04, 0xd9, 0x85, 0xa1, 0xc1, 0xa7, 0xde, 0xf8, + 0xd8, 0xf4, 0x1f, 0xf6, 0xd8, 0xf1, 0xa4, 0xf8, 0x82, 0x91, 0xaf, 0x31, 0xdb, 0x9f, 0x71, 0x92, + 0x41, 0xa7, 0xde, 0xd8, 0x84, 0x94, 0xaf, 0x19, 0xd9, 0xa8, 0xde, 0xf8, 0xf8, 0xf8, 0xa3, 0xdf, + 0xd8, 0x93, 0xfc, 0xc0, 0x0a, 0xd9, 0xa8, 0xde, 0xf8, 0xd8, 0xf4, 0x1f, 0xf6, 0xd8, 0xf1, 0xa4, + 0xf8, 0xa3, 0xfa, 0xf9, 0xd1, 0xdb, 0x88, 0x94, 0xaf, 0x41, 0x88, 0xa1, 0xc2, 0xd8, 0x93, 0xfc, + 0xc0, 0x0a, 0xd9, 0xa8, 0xde, 0xf8, 0xd8, 0xf1, 0x91, 0xfc, 0xc0, 0x04, 0xd9, 0xa7, 0xfa, 0xa3, + /* bank # 32 */ + 0xfa, 0xaf, 0xd0, 0xdf, 0xf8, 0xf8, 0xd8, 0xaf, 0xd0, 0xfa, 0xf9, 0xd1, 0xb0, 0xbc, 0xb4, 0xbd, + 0xb8, 0xbe, 0xda, 0xf3, 0xa5, 0x85, 0x9d, 0x08, 0xd8, 0xf1, 0xf1, 0xa7, 0xde, 0xf7, 0x84, 0x9f, + 0x6a, 0x87, 0xf1, 0xd4, 0xfd, 0x3e, 0xf9, 0xd9, 0xf4, 0x20, 0x48, 0xd8, 0xf0, 0xf7, 0xa7, 0x88, + 0x9f, 0x52, 0xf9, 0xd9, 0xf4, 0x20, 0x48, 0xd8, 0xf2, 0xbb, 0xa0, 0xf9, 0xda, 0xf4, 0x20, 0x48, + 0xd8, 0xf2, 0xb3, 0x80, 0xc4, 0xf4, 0x75, 0xdc, 0xd8, 0xf0, 0xb1, 0xb5, 0xba, 0x8a, 0x9a, 0xa7, + 0xf0, 0x2c, 0x50, 0x78, 0xf2, 0xa5, 0xde, 0xf8, 0xf8, 0xf1, 0xb5, 0xb2, 0xa7, 0x87, 0x90, 0x21, + 0xdb, 0xb6, 0xb1, 0x80, 0x97, 0x29, 0xd9, 0xf2, 0xa5, 0xf8, 0xd8, 0xbb, 0xb2, 0xb6, 0xbe, 0xa1, + 0xf8, 0xf9, 0xd1, 0xbe, 0xbe, 0xbe, 0xba, 0xda, 0xa5, 0xde, 0xd8, 0xa7, 0x82, 0x95, 0x65, 0xd1, + 0x85, 0xa2, 0xd0, 0xc1, 0xd9, 0xb5, 0xa7, 0x86, 0x93, 0x31, 0xdb, 0xd1, 0xf4, 0x20, 0x98, 0xd8, + 0xf3, 0xb8, 0xb0, 0xb4, 0xa5, 0x85, 0x9c, 0x18, 0xd8, 0xf1, 0xba, 0xb2, 0xb6, 0x81, 0x96, 0xa1, + 0xf8, 0xf9, 0xb9, 0xa6, 0xda, 0xc3, 0xc5, 0xc7, 0xd9, 0x2d, 0x4d, 0x6d, 0xd8, 0xba, 0x8a, 0xaa, + 0xf8, 0xf9, 0xb9, 0xae, 0xda, 0xc3, 0xc5, 0xc7, 0xd9, 0x2d, 0x4d, 0x6d, 0xd8, 0xba, 0x88, 0xa8, + 0xf8, 0xf9, 0xa7, 0xda, 0xc3, 0xc5, 0xc7, 0xd9, 0x2d, 0x4d, 0x6d, 0xd8, 0xf2, 0xb0, 0xb9, 0xa3, + 0xfa, 0xf9, 0xd1, 0xda, 0xb8, 0x8f, 0xa7, 0xc0, 0xf9, 0xb5, 0x87, 0x93, 0xf6, 0x0a, 0xf2, 0xb4, + 0xa4, 0x84, 0x97, 0x24, 0xa4, 0x84, 0x9e, 0x3c, 0xd8, 0xf3, 0xbe, 0xbe, 0xbb, 0xae, 0xf8, 0xf9, + 0xd1, 0xbe, 0xbe, 0xb0, 0xb4, 0xb8, 0xda, 0xa5, 0x85, 0x9e, 0x00, 0xd8, 0xf1, 0xbc, 0xbc, 0xbd, + /* bank # 33 */ + 0xbd, 0x8e, 0x9e, 0xa7, 0x59, 0xd1, 0xbc, 0xbc, 0xbd, 0xbd, 0xda, 0x85, 0x9e, 0xa5, 0x08, 0xd8, + 0xf1, 0xbc, 0xbc, 0x8e, 0xbe, 0xbe, 0xae, 0xd0, 0xc5, 0xbc, 0xbc, 0xbe, 0xbe, 0xf7, 0xb9, 0xb0, + 0xb5, 0xa6, 0x88, 0x95, 0x5a, 0xf9, 0xda, 0xf1, 0xab, 0xf8, 0xd8, 0xb8, 0xb4, 0xf3, 0x98, 0xfc, + 0xc0, 0x04, 0xda, 0xf4, 0x21, 0x86, 0xd8, 0xf2, 0xa9, 0xd0, 0xf8, 0x89, 0x9b, 0xa7, 0x51, 0xd9, + 0xa9, 0xd0, 0xde, 0xa4, 0x84, 0x9e, 0x2c, 0xd8, 0xa8, 0xfa, 0x88, 0x9a, 0xa7, 0x29, 0xd9, 0xa8, + 0xdf, 0xa4, 0x84, 0x9d, 0x34, 0xd8, 0xa8, 0xd0, 0xf8, 0x88, 0x9a, 0xa7, 0x51, 0xd9, 0xa8, 0xd0, + 0xde, 0xa4, 0x84, 0x9d, 0x2c, 0xd8, 0xa8, 0xd0, 0xfa, 0x88, 0x9a, 0xa7, 0x79, 0xd9, 0xa8, 0xd0, + 0xdf, 0xa4, 0x84, 0x9d, 0x24, 0xd8, 0xf3, 0xa9, 0xd0, 0xf8, 0x89, 0x9b, 0xa7, 0x51, 0xd9, 0xa9, + 0xd0, 0xde, 0xa4, 0x84, 0x9c, 0x2c, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, 0x52, 0xf9, 0xd9, 0xf4, 0x21, + 0xb6, 0xd8, 0xf1, 0xb9, 0xa2, 0xfa, 0xf3, 0xb8, 0xa9, 0xd0, 0xfa, 0x89, 0x9b, 0xa7, 0x79, 0xd9, + 0xa9, 0xd0, 0xdf, 0xa4, 0x84, 0x9c, 0x24, 0xd8, 0xf2, 0xa8, 0xf8, 0x88, 0x9a, 0xa7, 0x01, 0xd9, + 0xa8, 0xde, 0xa4, 0x84, 0x9d, 0x3c, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, 0x42, 0xf9, 0xd9, 0xf4, 0x21, + 0xfd, 0xd8, 0xf3, 0xa9, 0xf8, 0x89, 0x9b, 0xa7, 0x01, 0xd9, 0xa9, 0xde, 0xa4, 0x84, 0x9c, 0x3c, + 0xd8, 0xa9, 0xfa, 0x89, 0x9b, 0xa7, 0x29, 0xd9, 0xa9, 0xdf, 0xa4, 0x84, 0x9c, 0x34, 0xd8, 0xf2, + 0xa9, 0xfa, 0x89, 0x9b, 0xa7, 0x29, 0xd9, 0xa9, 0xdf, 0xa4, 0x84, 0x9e, 0x34, 0xd8, 0xa9, 0xd0, + 0xfa, 0x89, 0x9b, 0xa7, 0x79, 0xd9, 0xa9, 0xd0, 0xdf, 0xa4, 0x84, 0x9e, 0x24, 0xd8, 0xf1, 0xa7, + /* bank # 34 */ + 0xde, 0xf2, 0x84, 0xca, 0x97, 0xa4, 0x24, 0xa5, 0x94, 0xf6, 0x0a, 0xf7, 0x85, 0x02, 0xf8, 0xf9, + 0xd1, 0xd9, 0xf6, 0x9b, 0x02, 0xd8, 0xa7, 0xb1, 0x82, 0x95, 0x62, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, + 0x23, 0xf2, 0xd8, 0xf0, 0xb0, 0x85, 0xa4, 0xd0, 0xc0, 0xdd, 0xf2, 0xc0, 0xdc, 0xf6, 0xa7, 0x9f, + 0x02, 0xf9, 0xd9, 0xf3, 0xa5, 0xde, 0xda, 0xf0, 0xdd, 0xf2, 0xc8, 0xdc, 0xd8, 0x85, 0x95, 0xa5, + 0x00, 0xd9, 0x86, 0xf0, 0xdd, 0xf2, 0xca, 0xcc, 0xce, 0xdc, 0xd8, 0x85, 0x00, 0xd9, 0x80, 0xf0, + 0xdd, 0xf2, 0xcc, 0xc6, 0xce, 0x85, 0xca, 0xcc, 0xce, 0xdc, 0xd8, 0x85, 0x00, 0xd9, 0xb1, 0x89, + 0xf0, 0xdd, 0xf2, 0xc2, 0xca, 0xc4, 0xdc, 0xd8, 0xb0, 0x85, 0x00, 0xd9, 0x81, 0xf0, 0xdd, 0xf2, + 0xc6, 0xce, 0x82, 0xc0, 0xc8, 0xdc, 0xd8, 0x85, 0x00, 0xb1, 0xd9, 0x86, 0xf0, 0xdd, 0xf1, 0xc2, + 0xc4, 0xc6, 0xdc, 0xd8, 0xb0, 0xf2, 0x85, 0x00, 0xd9, 0xb2, 0x87, 0xf0, 0xdd, 0xf1, 0xc2, 0xc4, + 0xc6, 0xf2, 0xbc, 0xb0, 0x81, 0xc0, 0xdc, 0xbc, 0xbc, 0xbc, 0xd8, 0xb0, 0x85, 0x00, 0xb1, 0xd9, + 0x8f, 0xf0, 0xdd, 0xf2, 0xc2, 0xc4, 0xc6, 0xdc, 0xd8, 0xb0, 0x85, 0x00, 0xd9, 0xb1, 0x8e, 0xf0, + 0xdd, 0xf1, 0xc2, 0xc4, 0xc6, 0xf2, 0xbc, 0xb0, 0x81, 0xc0, 0xdc, 0xbc, 0xbc, 0xbc, 0xd8, 0xb0, + 0x85, 0x00, 0xd9, 0x82, 0xf0, 0xdd, 0xf2, 0xc2, 0xca, 0xc4, 0xdc, 0xd8, 0x85, 0x00, 0xd8, 0xf2, + 0x85, 0x00, 0xd9, 0xb1, 0x8a, 0xf0, 0xdd, 0xf1, 0xc2, 0xc4, 0xc6, 0xdc, 0xd8, 0xb0, 0xf2, 0x85, + 0x00, 0xd9, 0xb1, 0xf0, 0xdd, 0xf1, 0x82, 0xc4, 0xdc, 0xd8, 0xb0, 0xf3, 0xa5, 0xf8, 0xf9, 0xd1, + 0xd9, 0xf4, 0x23, 0x74, 0xd8, 0xf3, 0x85, 0x95, 0xa5, 0x00, 0x00, 0xd9, 0xbe, 0xf2, 0xba, 0xae, + /* bank # 35 */ + 0xde, 0xbe, 0xbe, 0xbe, 0xbc, 0xb2, 0x81, 0xf0, 0xdd, 0xf3, 0xc8, 0xdc, 0xbc, 0xbc, 0xbc, 0xd8, + 0xb0, 0xb8, 0x85, 0xa5, 0x00, 0xd9, 0xf2, 0xbe, 0xbe, 0xaa, 0xde, 0xbe, 0xbe, 0xbc, 0xbc, 0x8a, + 0xf0, 0xdd, 0xf3, 0xc0, 0xdc, 0xbc, 0xbc, 0xd8, 0x85, 0xa5, 0x00, 0xd9, 0xb9, 0xf2, 0xa3, 0xd0, + 0xde, 0xb2, 0x85, 0xf0, 0xdd, 0xf3, 0xc8, 0xdc, 0xd8, 0xb0, 0x85, 0xb8, 0xa5, 0x00, 0xd9, 0xb3, + 0x8a, 0xf0, 0xdd, 0xf3, 0xc0, 0xdc, 0xd8, 0xb0, 0x85, 0x00, 0xd9, 0x8f, 0xf0, 0xdd, 0xf3, 0xc4, + 0xdc, 0xd8, 0x85, 0x00, 0x00, 0x00, 0xd9, 0xbc, 0xbc, 0xb3, 0x8e, 0xf0, 0xdd, 0xf3, 0xc0, 0xf1, + 0xc2, 0xdc, 0xbc, 0xbc, 0xd8, 0xf3, 0xb0, 0x85, 0x00, 0xd9, 0xbc, 0xbc, 0x8e, 0xf0, 0xdd, 0xf3, + 0xc4, 0xdc, 0xbc, 0xbc, 0xd8, 0xf3, 0xb0, 0x8e, 0xf4, 0xb8, 0xa7, 0xd0, 0xc0, 0xd8, 0x87, 0xf3, + 0xb9, 0xa2, 0xc6, 0xa6, 0xc4, 0xf7, 0xb5, 0x8e, 0x96, 0x06, 0xf8, 0xf9, 0xd1, 0xda, 0xf4, 0x23, + 0x7d, 0xd8, 0xf3, 0x8e, 0xc0, 0xf9, 0xb1, 0x86, 0x96, 0xf7, 0x0a, 0xdf, 0xf3, 0x30, 0xfd, 0x08, + 0xa2, 0x82, 0x10, 0xf0, 0xdd, 0xf3, 0x82, 0xc0, 0xdc, 0xf2, 0xb9, 0xa3, 0xdf, 0xf4, 0xb1, 0x8c, + 0xf3, 0xaf, 0xc1, 0xc3, 0xaf, 0x8f, 0xb4, 0x9d, 0x3e, 0xfd, 0x1e, 0xb5, 0x9f, 0x30, 0xa6, 0x39, + 0xd9, 0xf4, 0x23, 0xec, 0xd8, 0xf7, 0xb8, 0xb0, 0xb4, 0xa7, 0x84, 0x9d, 0x1a, 0xf9, 0xd9, 0xf4, + 0x23, 0xdf, 0xd8, 0xf1, 0xb9, 0xb1, 0xb5, 0xa6, 0x83, 0x9b, 0x61, 0xd9, 0xf4, 0x23, 0xf2, 0xd8, + 0xf6, 0xb8, 0xb0, 0xb4, 0xa7, 0x84, 0x94, 0x5a, 0xf8, 0xf9, 0xd1, 0xda, 0xf0, 0xe2, 0xf1, 0xb9, + 0xab, 0xde, 0xd8, 0xf2, 0xb1, 0x86, 0xb9, 0xaf, 0xc3, 0xc5, 0xc7, 0xb8, 0xb0, 0xb4, 0xa7, 0x88, + /* bank # 36 */ + 0x9c, 0xf7, 0x6a, 0xf9, 0xd9, 0xff, 0xd8, 0x72, 0xb9, 0xab, 0xf1, 0xdf, 0xf7, 0x62, 0xf3, 0xf8, + 0xf9, 0xd1, 0xda, 0xf1, 0xde, 0xf8, 0xd8, 0xf7, 0xbb, 0xaf, 0x7a, 0x9d, 0x66, 0x9e, 0x76, 0x9f, + 0x76, 0xf1, 0xa1, 0xdf, 0xba, 0xa6, 0xd0, 0xde, 0xbb, 0xf3, 0xa0, 0xf9, 0xda, 0xff, 0xd8, 0xb3, + 0x80, 0xc4, 0xaf, 0xd0, 0xfa, 0xf9, 0xd1, 0xda, 0xbc, 0xbc, 0xbc, 0xf4, 0x25, 0xba, 0xd8, 0xf1, + 0xb8, 0xbe, 0xbe, 0xae, 0xd0, 0xde, 0xb0, 0x84, 0xba, 0xbe, 0xa7, 0xc1, 0xf7, 0x88, 0xb4, 0x9d, + 0x6e, 0xf9, 0xb2, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xda, 0xf4, 0x24, 0x8f, 0xd8, 0xf1, 0xb8, + 0xbe, 0xbe, 0xbe, 0xae, 0xd0, 0x91, 0xfc, 0xc0, 0x00, 0xdb, 0xb6, 0x95, 0xfc, 0xc1, 0x04, 0xd9, + 0xf8, 0xf8, 0xf8, 0xf8, 0xd8, 0xb4, 0x91, 0xfc, 0xc0, 0x04, 0xdb, 0xb6, 0x95, 0xfc, 0xc1, 0x00, + 0xd9, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xd8, 0xba, 0xbe, 0xf4, 0x24, 0xf6, 0xd8, + 0xf1, 0x91, 0xfc, 0xc0, 0x00, 0xdb, 0xb6, 0x95, 0xfc, 0xc1, 0x04, 0xf5, 0x87, 0x95, 0xa7, 0x3a, + 0xf1, 0xf9, 0xd9, 0xaf, 0xde, 0x8f, 0xbe, 0xbe, 0xa1, 0xf4, 0xc1, 0xf1, 0xa2, 0xf4, 0xc1, 0xf1, + 0xbe, 0xbe, 0xd8, 0xb4, 0x91, 0xfc, 0xc0, 0x04, 0xdb, 0xb6, 0x95, 0xfc, 0xc1, 0x00, 0xd9, 0xaf, + 0xde, 0xf8, 0xfd, 0x07, 0x8f, 0x95, 0x10, 0xdf, 0xf8, 0xf8, 0xf8, 0xa7, 0xde, 0xf8, 0xfd, 0x07, + 0xdf, 0xf8, 0xfd, 0x06, 0xdf, 0xf8, 0xfd, 0x04, 0x8f, 0x97, 0xaf, 0xd0, 0xde, 0x40, 0x48, 0x50, + 0xdf, 0xf8, 0x60, 0x8f, 0xbe, 0xbe, 0xa0, 0xd0, 0xf4, 0xc1, 0xf1, 0xa1, 0xf4, 0xc2, 0xc5, 0xf1, + 0xa2, 0xf4, 0xc7, 0xf1, 0xbe, 0xbe, 0xd8, 0xf1, 0xb0, 0x81, 0xa5, 0xc1, 0xbc, 0x84, 0xb8, 0xbe, + /* bank # 37 */ + 0xbe, 0xa9, 0xc1, 0xf7, 0x88, 0xb4, 0xbd, 0x9d, 0x6e, 0xf9, 0xbc, 0xbd, 0xda, 0xf4, 0x25, 0x43, + 0xd8, 0xf1, 0xa9, 0xde, 0xf8, 0xfd, 0x04, 0xdf, 0xf8, 0xfd, 0x05, 0xbc, 0x8e, 0xbe, 0xae, 0xd0, + 0x9a, 0xfc, 0xc0, 0x00, 0xdb, 0x9b, 0xfc, 0xc0, 0x04, 0xd9, 0x99, 0x40, 0xd8, 0x9a, 0xfc, 0xc0, + 0x04, 0xdb, 0x9b, 0xfc, 0xc0, 0x00, 0xd9, 0x99, 0x48, 0xd8, 0xbc, 0xbc, 0xbc, 0xbe, 0xbe, 0xbe, + 0xf4, 0x25, 0xad, 0xd8, 0xf1, 0x9a, 0xfc, 0xc0, 0x00, 0xdb, 0x9b, 0xfc, 0xc0, 0x04, 0xf5, 0x89, + 0xa9, 0x32, 0xf9, 0xd9, 0xf1, 0xde, 0xf8, 0xfd, 0x02, 0xdf, 0xf8, 0xfd, 0x07, 0xdf, 0xf8, 0xfd, + 0x07, 0xf8, 0xdf, 0x89, 0xba, 0xa0, 0xf4, 0xc0, 0xf1, 0x8b, 0xa1, 0xd0, 0xf4, 0xc3, 0xf1, 0x89, + 0xa2, 0xf4, 0xc2, 0xc5, 0xc7, 0xf1, 0xa3, 0xf4, 0xc7, 0xf1, 0xb8, 0xd8, 0x9a, 0xfc, 0xc0, 0x04, + 0xdb, 0x9b, 0xfc, 0xc0, 0x00, 0xd9, 0xa9, 0xde, 0xf8, 0xfd, 0x02, 0xdf, 0xf8, 0xfd, 0x07, 0xdf, + 0xf8, 0xfd, 0x07, 0xf8, 0xdf, 0xf8, 0xfd, 0x04, 0xf9, 0x89, 0xba, 0xa0, 0xf4, 0xc0, 0xf1, 0x8b, + 0xa1, 0xd0, 0xf4, 0xc3, 0xf1, 0x89, 0xa2, 0xf4, 0xc2, 0xc5, 0xc7, 0xf1, 0xb8, 0xd8, 0xf1, 0x8a, + 0xab, 0xc0, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbe, 0xbe, 0xbe, 0xd8, 0xf1, 0xb2, 0x80, 0xba, 0xa7, + 0xc4, 0xbc, 0xb2, 0x8b, 0xf4, 0x75, 0x75, 0x8f, 0xb6, 0x9c, 0xf4, 0x75, 0x81, 0xaf, 0xf4, 0x75, + 0x87, 0x8b, 0xf4, 0x75, 0x75, 0x8e, 0xb6, 0x9d, 0xf4, 0x75, 0x81, 0xae, 0xf4, 0x75, 0x87, 0xb3, + 0x81, 0xf4, 0x75, 0x75, 0x85, 0x94, 0xf4, 0x75, 0x81, 0xbb, 0xa5, 0xf4, 0x75, 0x87, 0x80, 0xba, + 0xf4, 0x75, 0x75, 0xb3, 0x8e, 0x9b, 0xf4, 0x75, 0x81, 0xbb, 0xae, 0xf4, 0x75, 0x87, 0xb3, 0x83, + /* bank # 38 */ + 0xa3, 0xf4, 0x75, 0x93, 0xf1, 0xb2, 0x8f, 0xb6, 0x9f, 0xbe, 0xbe, 0xb9, 0xaf, 0x7a, 0x8e, 0x9e, + 0x7e, 0xf5, 0xb3, 0x85, 0xb7, 0x95, 0x7c, 0x8e, 0x9e, 0x7c, 0xf1, 0xbc, 0xbc, 0xbd, 0xbd, 0xb1, + 0xb5, 0x8f, 0x9f, 0xaf, 0xd0, 0x58, 0x82, 0xaf, 0x01, 0x2d, 0x55, 0x86, 0xaf, 0x42, 0x4e, 0x76, + 0x82, 0xa2, 0x00, 0x2c, 0x54, 0x84, 0xbd, 0xb6, 0x90, 0xaf, 0x51, 0xbd, 0xbd, 0xbd, 0xb5, 0x9f, + 0x06, 0xa4, 0xd0, 0x48, 0x8f, 0xaf, 0xd0, 0x0a, 0x84, 0x74, 0xa4, 0xd0, 0x3e, 0x80, 0x93, 0xaf, + 0x39, 0xd1, 0xab, 0xd9, 0xfa, 0xda, 0xdf, 0xd8, 0xba, 0xad, 0xfa, 0x83, 0x9b, 0xa7, 0x69, 0xdb, + 0xb2, 0x8d, 0xb6, 0x9d, 0x69, 0xf4, 0x26, 0x6d, 0xd8, 0xf1, 0xad, 0xde, 0xdf, 0xd8, 0xf0, 0xbc, + 0xb2, 0x81, 0xbd, 0xb6, 0x91, 0xbb, 0xa6, 0x3c, 0x11, 0x0c, 0x58, 0x2c, 0x50, 0xf1, 0xbc, 0xbc, + 0xbc, 0xb3, 0x86, 0xbd, 0xbd, 0xbd, 0xb7, 0x96, 0xa6, 0x2c, 0x54, 0x7c, 0x9b, 0x71, 0x97, 0xa5, + 0xd0, 0x2a, 0xf0, 0x50, 0x78, 0xf1, 0xd8, 0xb8, 0xac, 0xde, 0xf8, 0xf5, 0xb0, 0x8c, 0xb7, 0x93, + 0x06, 0xf1, 0xf9, 0xaf, 0xda, 0xf8, 0xd9, 0xde, 0xd8, 0xb3, 0xb6, 0xba, 0x86, 0xa7, 0xc2, 0xf4, + 0x75, 0x9b, 0x93, 0xf0, 0x71, 0x71, 0x60, 0x84, 0x92, 0xf4, 0x75, 0x81, 0xf1, 0xa4, 0xf4, 0x75, + 0x87, 0x83, 0xa3, 0xf4, 0x75, 0x93, 0xb3, 0x86, 0xa7, 0xc4, 0xf4, 0x75, 0x9b, 0x95, 0xf0, 0x71, + 0x71, 0x60, 0x86, 0x92, 0xf4, 0x75, 0x81, 0xa6, 0xf4, 0x75, 0x87, 0x85, 0xa5, 0xf4, 0x75, 0x93, + 0xb3, 0x86, 0xa7, 0xc6, 0xf4, 0x75, 0x9b, 0x9f, 0xf0, 0x71, 0x71, 0x60, 0x88, 0x92, 0xf4, 0x75, + 0x81, 0xa8, 0xf4, 0x75, 0x87, 0x8f, 0xaf, 0xf4, 0x75, 0x93, 0xf5, 0xb2, 0x84, 0x94, 0xb9, 0xaf, + /* bank # 39 */ + 0x7c, 0x86, 0x96, 0x7c, 0x88, 0x98, 0x7c, 0xf1, 0xb1, 0x8f, 0xb5, 0x9f, 0xa5, 0x30, 0x85, 0x18, + 0xf0, 0x9a, 0x3c, 0x99, 0x18, 0xf1, 0xbc, 0xbc, 0xb2, 0x84, 0xb9, 0xaf, 0xc3, 0xc5, 0xc7, 0xba, + 0xb6, 0xbc, 0xbc, 0xa7, 0x8b, 0xb5, 0x9f, 0x2d, 0x55, 0x7d, 0xf5, 0xa7, 0x87, 0xb6, 0x97, 0x2c, + 0x54, 0x7c, 0xf0, 0xac, 0x81, 0x9c, 0x0c, 0x97, 0x28, 0x9c, 0x14, 0x97, 0x30, 0x9c, 0x1c, 0x97, + 0x38, 0xf1, 0xb1, 0x8f, 0xab, 0xc3, 0xc5, 0xc7, 0xa7, 0xb2, 0x81, 0x9c, 0x59, 0xdb, 0x51, 0xaa, + 0xde, 0xf4, 0x27, 0x6a, 0xd8, 0xf1, 0xac, 0xb1, 0x8e, 0x9c, 0x48, 0xfd, 0x02, 0xb2, 0x8b, 0x02, + 0xaa, 0xde, 0xa7, 0x8c, 0x11, 0xdb, 0x19, 0xda, 0xaa, 0xf8, 0xd8, 0xf1, 0xb5, 0xbd, 0xbd, 0x9b, + 0xfc, 0xc1, 0x03, 0xbd, 0xbd, 0xd9, 0xf4, 0x28, 0xea, 0xd8, 0xf1, 0xb2, 0xbc, 0xbc, 0x84, 0xb8, + 0xbe, 0xae, 0xc3, 0xc5, 0xc7, 0xb0, 0xbc, 0xbc, 0xbc, 0xb4, 0xbd, 0xf0, 0x8a, 0x9e, 0xaf, 0x6c, + 0x99, 0x61, 0x8a, 0x19, 0x9e, 0x74, 0x99, 0x69, 0x8a, 0x39, 0x9e, 0x7c, 0x99, 0x71, 0x8a, 0x59, + 0xf1, 0x8f, 0x9f, 0xaa, 0x28, 0xfd, 0x01, 0x54, 0xfd, 0x01, 0x7c, 0xfd, 0x01, 0x8e, 0xa9, 0xc2, + 0xc5, 0xc7, 0xf0, 0x8a, 0x9a, 0xa7, 0x04, 0x28, 0x50, 0xf1, 0x87, 0x97, 0xaf, 0x09, 0x8f, 0xb5, + 0xbd, 0xbd, 0xbd, 0x9b, 0x1e, 0xb4, 0xbd, 0x97, 0xa7, 0x20, 0x8b, 0xba, 0xa7, 0xc1, 0xc3, 0xc5, + 0xbd, 0xb6, 0x90, 0xfc, 0xc2, 0x00, 0xbd, 0xbd, 0xbd, 0xd9, 0xf4, 0x28, 0x77, 0xd8, 0xf1, 0xb2, + 0x86, 0xb6, 0x97, 0xa7, 0x4a, 0x99, 0xf4, 0x75, 0xa1, 0x9a, 0xf4, 0x75, 0x81, 0x8a, 0xaa, 0xf4, + 0x75, 0x93, 0xf1, 0x86, 0x97, 0xa7, 0x52, 0x9b, 0xf4, 0x75, 0xa1, 0x9c, 0xf4, 0x75, 0x81, 0x8c, + /* bank # 40 */ + 0xac, 0xf4, 0x75, 0x93, 0xf1, 0x86, 0x97, 0xa7, 0x5a, 0x9d, 0xf4, 0x75, 0xa1, 0x9e, 0xf4, 0x75, + 0x81, 0x8e, 0xae, 0xf4, 0x75, 0x93, 0xf1, 0x89, 0xa9, 0xc2, 0xc5, 0xc7, 0x87, 0xc3, 0x8b, 0xab, + 0xc2, 0xc5, 0xc7, 0x87, 0xc5, 0x8d, 0xad, 0xc2, 0xc5, 0xc7, 0x87, 0xc7, 0xb8, 0xae, 0xde, 0x8a, + 0xb4, 0x9e, 0x64, 0xfd, 0x01, 0x8c, 0x64, 0xfd, 0x01, 0x8e, 0x64, 0xfd, 0x01, 0xb0, 0xf0, 0x8d, + 0x9e, 0xaf, 0x6c, 0x9c, 0x61, 0x8d, 0x19, 0x9e, 0x74, 0x9c, 0x69, 0x8d, 0x39, 0x9e, 0x7c, 0x9c, + 0x71, 0x8d, 0x59, 0xf1, 0x8f, 0x9f, 0xad, 0x28, 0xfd, 0x01, 0x54, 0xfd, 0x01, 0x7c, 0xfd, 0x01, + 0x8e, 0xac, 0xc2, 0xc5, 0xc7, 0xf0, 0x8d, 0x9d, 0xa8, 0x04, 0x28, 0x50, 0xf1, 0x88, 0x98, 0xaf, + 0x09, 0x8f, 0x9b, 0x1e, 0x98, 0xa8, 0x20, 0xd8, 0xf1, 0xb8, 0xb1, 0xb4, 0xbc, 0xbc, 0xbc, 0x84, + 0xaf, 0xc7, 0x87, 0xc1, 0xb3, 0x83, 0xc1, 0xbc, 0xb0, 0x8f, 0x9f, 0xaf, 0x49, 0xda, 0xf4, 0x28, + 0xa7, 0xd8, 0xf5, 0x91, 0x7a, 0xf1, 0x9f, 0xfc, 0xc0, 0x03, 0xdb, 0x90, 0xfc, 0xc0, 0x00, 0xd9, + 0xa1, 0xde, 0xf8, 0xd8, 0xf4, 0x28, 0xb7, 0xd8, 0xf5, 0x91, 0x72, 0xf1, 0x9f, 0xfc, 0xc0, 0x03, + 0xd9, 0xa1, 0xde, 0xdf, 0xa0, 0xde, 0xdf, 0xd8, 0xf1, 0xa1, 0xf8, 0xf9, 0xd1, 0xa0, 0xda, 0xf8, + 0xd9, 0xfa, 0xd8, 0x80, 0x90, 0xaf, 0x11, 0xdb, 0xa1, 0xde, 0x91, 0xfc, 0xc1, 0x04, 0xd9, 0xa1, + 0xf8, 0xdf, 0xa0, 0xde, 0xd8, 0x80, 0x90, 0xaf, 0x39, 0xd9, 0xa0, 0xde, 0xdf, 0xa1, 0xdf, 0xd8, + 0xf1, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbe, 0xbe, 0xbe, 0xd8, 0xf1, 0xb1, 0xb5, 0xb9, 0xa6, + 0xf8, 0x8a, 0xbb, 0xa4, 0xc3, 0xa0, 0xc5, 0xb9, 0x86, 0x96, 0xaf, 0x21, 0xd9, 0xf4, 0x30, 0x31, + /* bank # 41 */ + 0xd8, 0xf1, 0xa6, 0xde, 0xa1, 0xde, 0xdf, 0xdf, 0xa0, 0xde, 0xdf, 0xdf, 0xdf, 0xab, 0xde, 0xac, + 0xde, 0xb3, 0x8c, 0xbb, 0xa4, 0xd0, 0xc4, 0xa0, 0xd0, 0xc6, 0xb8, 0xbe, 0xbe, 0xbe, 0x83, 0xa9, + 0xc1, 0xf2, 0xbc, 0xbc, 0x82, 0xc3, 0x81, 0xc5, 0xf8, 0xf1, 0xb0, 0xbc, 0xbd, 0xbd, 0x9b, 0xfc, + 0xc1, 0x03, 0xb4, 0xbd, 0xd9, 0xf4, 0x29, 0x84, 0xd8, 0xf1, 0xaa, 0xde, 0x99, 0xfc, 0xc1, 0x00, + 0xd9, 0xaa, 0xfa, 0xdb, 0x8a, 0x9a, 0xa9, 0x39, 0xaa, 0xde, 0xf8, 0xd8, 0xf5, 0xa2, 0x89, 0x92, + 0x3a, 0xf1, 0x92, 0xfc, 0xc0, 0x03, 0xda, 0xdf, 0xd9, 0xfa, 0xa2, 0x82, 0xdb, 0x31, 0xdf, 0xaa, + 0xde, 0xf8, 0xd8, 0x99, 0xfc, 0xc1, 0x03, 0xd9, 0xaa, 0xdf, 0xd8, 0xf2, 0x89, 0x99, 0xa9, 0x71, + 0xdb, 0xde, 0x41, 0xf1, 0xaa, 0xde, 0xf8, 0xd8, 0x9a, 0xfc, 0xc0, 0x04, 0xdb, 0xa8, 0xde, 0x98, + 0xfc, 0xc1, 0x00, 0xf8, 0xd8, 0xf1, 0xb1, 0xbc, 0xb5, 0xbd, 0xb9, 0xbe, 0x87, 0x94, 0xaf, 0x19, + 0xd9, 0x83, 0xa1, 0xc6, 0xf4, 0x2c, 0x7a, 0xd8, 0xf1, 0x82, 0x9f, 0xaf, 0xdf, 0x28, 0xfd, 0x03, + 0xdf, 0x30, 0xfd, 0x04, 0x8f, 0x9f, 0x34, 0x82, 0x38, 0x1d, 0xa9, 0xde, 0xd9, 0xf8, 0xda, 0xf4, + 0x2a, 0xeb, 0xd8, 0xf1, 0x82, 0x97, 0xaf, 0x51, 0xd9, 0x83, 0xa0, 0xc7, 0x83, 0xa7, 0xd0, 0xc2, + 0xf4, 0x2a, 0x1c, 0xd8, 0xf1, 0x82, 0x92, 0xaf, 0x59, 0xda, 0xf4, 0x2a, 0x1c, 0xd8, 0xf5, 0xb3, + 0x83, 0xb7, 0x99, 0x1a, 0xf1, 0xf8, 0xf9, 0xd1, 0xda, 0xb1, 0xb5, 0xf4, 0x2a, 0x1c, 0xd8, 0xf5, + 0x3a, 0xf1, 0xf8, 0xf9, 0xd1, 0xda, 0xb1, 0xb5, 0xf4, 0x2a, 0x1c, 0xd8, 0xf1, 0xb0, 0xbc, 0xbc, + 0xbc, 0x88, 0xaf, 0xc1, 0xf2, 0x89, 0xc5, 0xc7, 0xf9, 0xf9, 0xb1, 0xbc, 0xb5, 0xb9, 0xf2, 0x8f, + /* bank # 42 */ + 0x9f, 0xaf, 0x71, 0xd9, 0xf1, 0x83, 0xa0, 0xc6, 0xb3, 0x8c, 0xbb, 0xa4, 0xd0, 0xc4, 0xa0, 0xd0, + 0xc6, 0xb1, 0xb9, 0xd8, 0xf1, 0x83, 0xac, 0xc6, 0x83, 0xa7, 0xd0, 0xc4, 0xd8, 0xf1, 0xbc, 0xbc, + 0x81, 0xaf, 0xc3, 0xf3, 0x8b, 0xc3, 0xf2, 0xb3, 0x82, 0xc2, 0x81, 0xc5, 0xf9, 0xf1, 0xb1, 0xbc, + 0xbc, 0x83, 0x9f, 0xaf, 0x09, 0xdb, 0x8f, 0x9e, 0x31, 0x83, 0xa1, 0xc7, 0xa0, 0xdf, 0xd0, 0xde, + 0x9f, 0xfc, 0xc2, 0x01, 0xd9, 0xf2, 0xaf, 0xde, 0xf8, 0xf8, 0xf8, 0x8f, 0xdb, 0x41, 0xd9, 0xf1, + 0x8e, 0xb7, 0x91, 0xbb, 0xa2, 0xd0, 0x5c, 0xfd, 0x3f, 0xb5, 0xb9, 0xd8, 0x8f, 0x93, 0xaf, 0x21, + 0xdb, 0x83, 0xa0, 0xc7, 0xd0, 0xde, 0xa1, 0xdf, 0x9f, 0xfc, 0xc2, 0x01, 0xd9, 0xf2, 0xaf, 0xde, + 0xf8, 0xf8, 0xf8, 0x8f, 0xdb, 0x41, 0xd9, 0xf1, 0x8e, 0xb7, 0x91, 0xbb, 0xa2, 0xd0, 0x5c, 0xfd, + 0x3f, 0xb5, 0xb9, 0xd8, 0xf1, 0x9f, 0xfc, 0xc2, 0x01, 0xd9, 0xf4, 0x2a, 0xba, 0xd8, 0xf3, 0xbc, + 0xbc, 0xaf, 0xd0, 0xb1, 0x8c, 0xc4, 0xf1, 0xb0, 0xbc, 0x8a, 0xaf, 0xc5, 0xb1, 0xbc, 0x80, 0x93, + 0xaf, 0x39, 0xd1, 0xd9, 0xf3, 0xd0, 0xf8, 0xf9, 0xdb, 0xd1, 0xf1, 0x9f, 0xfc, 0xc1, 0x04, 0xf2, + 0x8f, 0x9f, 0xaf, 0x59, 0xf1, 0xa0, 0xdf, 0x83, 0xd0, 0xc6, 0xd8, 0xf1, 0xa1, 0xd0, 0xde, 0x83, + 0x90, 0xaf, 0x69, 0xdb, 0x91, 0x69, 0xf4, 0x2a, 0xd4, 0xd8, 0xf2, 0x8f, 0x9f, 0x71, 0xd9, 0xf1, + 0x83, 0xa1, 0xd0, 0xc6, 0xd8, 0xf1, 0x80, 0x93, 0xaf, 0x19, 0xd1, 0xd9, 0xf4, 0x2b, 0x5a, 0xd8, + 0xf1, 0x79, 0xd1, 0xd9, 0xf4, 0x2b, 0x5a, 0xd8, 0xf4, 0x2c, 0xbb, 0xd8, 0xf1, 0x82, 0x9d, 0xaf, + 0x31, 0xda, 0xf4, 0x2b, 0x1c, 0xd8, 0xf1, 0x83, 0xa0, 0xd0, 0xc7, 0xb6, 0x9d, 0xfc, 0xc2, 0x04, + /* bank # 43 */ + 0xd9, 0xba, 0xad, 0xde, 0xf8, 0xd8, 0xb3, 0x8a, 0xb7, 0x92, 0xbb, 0xaf, 0x19, 0xb1, 0x88, 0xa4, + 0xd9, 0xc5, 0xa0, 0xc7, 0xda, 0xc1, 0xa0, 0xc3, 0xd8, 0xf4, 0x2b, 0x5a, 0xd8, 0xf1, 0xa1, 0xf8, + 0xf9, 0xd1, 0xda, 0xf4, 0x2b, 0x5a, 0xd8, 0xf1, 0xba, 0xad, 0xf8, 0xf9, 0xd1, 0xd9, 0x83, 0xb9, + 0xa0, 0xc6, 0xab, 0xc6, 0xb3, 0x8d, 0xbb, 0xa4, 0xd0, 0xc4, 0xa0, 0xd0, 0xc6, 0xf4, 0x2b, 0x5a, + 0xd8, 0xf1, 0x83, 0xb9, 0xa0, 0xd0, 0xc7, 0xb3, 0x8a, 0xb7, 0x92, 0xbb, 0xaf, 0x19, 0xb1, 0xa4, + 0xd9, 0x89, 0xc3, 0xa0, 0xc5, 0xda, 0x88, 0xc1, 0xa0, 0xc3, 0xd8, 0xf1, 0xb1, 0x85, 0xba, 0xbe, + 0xaf, 0xc2, 0x84, 0xc7, 0x82, 0xc1, 0xc3, 0xb2, 0xbc, 0xb6, 0xbd, 0xa7, 0xdf, 0xdf, 0x8f, 0x92, + 0xa7, 0x01, 0xd9, 0xf4, 0x2b, 0x9c, 0xd8, 0xf1, 0x09, 0xd9, 0xf4, 0x2b, 0x83, 0xd8, 0xf1, 0xfa, + 0xf4, 0x2b, 0xcb, 0xd8, 0xf1, 0x51, 0xd9, 0xf4, 0x2b, 0x90, 0xd8, 0xf1, 0xfa, 0xf4, 0x2b, 0xcb, + 0xd8, 0xf1, 0x19, 0xd9, 0xd0, 0xf8, 0xda, 0xfa, 0xd8, 0xf4, 0x2b, 0xcb, 0xd8, 0xf1, 0x93, 0x21, + 0xd9, 0xf4, 0x2b, 0xb0, 0xd8, 0xf1, 0x09, 0xd9, 0xd0, 0xf8, 0xda, 0xfa, 0xd8, 0xf4, 0x2b, 0xcb, + 0xd8, 0xf1, 0x71, 0xd9, 0xd0, 0xf8, 0xf4, 0x2b, 0xcb, 0xd8, 0xf1, 0x59, 0xd9, 0xd0, 0xf8, 0xf4, + 0x2b, 0xcb, 0xd8, 0xf1, 0x94, 0x01, 0xd9, 0xd0, 0xf8, 0xda, 0xfa, 0xd8, 0xf1, 0xb0, 0xbc, 0xbc, + 0x88, 0xa7, 0xc0, 0xb1, 0xbc, 0x89, 0xd0, 0xc1, 0x82, 0xaf, 0xd0, 0xc5, 0xb2, 0xbc, 0xb5, 0xbd, + 0x9b, 0xfc, 0xc1, 0x00, 0xb6, 0xbd, 0xbd, 0xbd, 0xdb, 0x97, 0xfc, 0xc3, 0x04, 0xfc, 0xc0, 0x00, + 0xfc, 0xc2, 0x04, 0xd9, 0xa7, 0xdf, 0xf8, 0xdf, 0xd8, 0xf1, 0x8f, 0x94, 0xa7, 0x71, 0xd9, 0xf4, + /* bank # 44 */ + 0x2c, 0x14, 0xd8, 0xf1, 0x95, 0x41, 0xd9, 0xf4, 0x2c, 0x14, 0xd8, 0xf1, 0x94, 0x09, 0xdb, 0x39, + 0xd9, 0xdf, 0xdf, 0xf8, 0xd8, 0xf1, 0x97, 0xfc, 0xc1, 0x04, 0xb1, 0xbc, 0xbc, 0xbc, 0x83, 0xb9, + 0xbe, 0xbe, 0xbe, 0xa0, 0xd9, 0xc6, 0xda, 0xde, 0xd8, 0xfc, 0xc2, 0x04, 0xd0, 0xd9, 0xc7, 0xda, + 0xdf, 0xd8, 0x8e, 0xb5, 0xbd, 0x9b, 0xaf, 0x4c, 0xbd, 0xbd, 0x9f, 0xfc, 0xc1, 0x00, 0xd9, 0xf4, + 0x2c, 0xbb, 0xd8, 0xf0, 0xb3, 0x86, 0xb6, 0x9a, 0xbb, 0xab, 0x2c, 0x50, 0x78, 0xf1, 0xba, 0xaa, + 0xc3, 0xc5, 0xc7, 0xb8, 0xad, 0xf8, 0xf9, 0xd1, 0xda, 0xde, 0xb3, 0x8e, 0xbb, 0xab, 0xc7, 0xd8, + 0xb3, 0x8e, 0xb7, 0x9b, 0xba, 0xa7, 0x69, 0xd9, 0xb1, 0x83, 0xb5, 0x90, 0x79, 0xdb, 0xd1, 0xb9, + 0xa0, 0xd0, 0xdf, 0xa1, 0xd0, 0xc6, 0xd8, 0xf4, 0x2c, 0xbb, 0xd8, 0xf1, 0xb0, 0xbc, 0x81, 0xb9, + 0xaf, 0xc0, 0xb0, 0x88, 0xc1, 0x87, 0xc1, 0xb1, 0xbc, 0xbc, 0xbc, 0xb5, 0xbd, 0xbd, 0x9b, 0xfc, + 0xc1, 0x00, 0xbd, 0xbd, 0xdb, 0x9f, 0xfc, 0xc0, 0x04, 0x8f, 0x9e, 0x2d, 0x8d, 0x9f, 0x31, 0xd9, + 0xa1, 0xde, 0x83, 0xa0, 0xc6, 0xaf, 0xde, 0xf8, 0xb3, 0x83, 0x9f, 0xf5, 0x06, 0xf1, 0xdb, 0xfc, + 0xc1, 0x04, 0xd9, 0xb8, 0xbe, 0xa1, 0xdf, 0xf8, 0xbe, 0xbe, 0xbe, 0xd8, 0xf5, 0xb3, 0x89, 0xb7, + 0x93, 0xbb, 0xa9, 0x66, 0x8b, 0xaf, 0x02, 0xf1, 0x9f, 0xfc, 0xc0, 0x03, 0xd9, 0x8f, 0xa9, 0xd0, + 0xc0, 0xd8, 0x89, 0x99, 0xa3, 0x34, 0xaf, 0xde, 0xf8, 0xf5, 0x83, 0x9f, 0x06, 0xf1, 0xfc, 0xc1, + 0x04, 0xdb, 0x95, 0x71, 0xa2, 0xd0, 0xde, 0xd8, 0xb0, 0x8d, 0xb9, 0xa1, 0xd0, 0xc7, 0x8f, 0xb4, + 0x9f, 0xaf, 0x11, 0xd9, 0xa1, 0xd0, 0xc7, 0xd8, 0xf1, 0xb3, 0x89, 0xbb, 0xaf, 0xc6, 0xf9, 0xf5, + /* bank # 45 */ + 0x8f, 0xb7, 0x93, 0x06, 0xf1, 0x9f, 0xfc, 0xc1, 0x03, 0xdb, 0x83, 0xa9, 0xc0, 0xd8, 0xa3, 0xde, + 0xb9, 0xa0, 0xd0, 0xde, 0xba, 0xaa, 0xf8, 0xf9, 0xd1, 0xda, 0xf4, 0x2d, 0x8e, 0xd8, 0xf1, 0xb9, + 0xb1, 0xb5, 0xaf, 0x83, 0x90, 0x61, 0xdb, 0x69, 0x79, 0x91, 0x69, 0xf4, 0x2d, 0x85, 0xd8, 0xf1, + 0xdf, 0xf8, 0xa0, 0xfa, 0xf9, 0xd1, 0xd9, 0xaf, 0xdf, 0xd8, 0xaf, 0x8c, 0x95, 0x69, 0xd9, 0xdf, + 0xd8, 0xaf, 0x85, 0x9c, 0x31, 0xdb, 0x9f, 0xfc, 0xc1, 0x00, 0xda, 0xf4, 0x2d, 0x62, 0xd8, 0xf1, + 0x83, 0xa0, 0xd0, 0xc6, 0xaf, 0x8a, 0x9e, 0x11, 0xf8, 0xd9, 0xa0, 0xd0, 0x80, 0x9c, 0x48, 0xd8, + 0xaa, 0xde, 0xd8, 0xf1, 0xb3, 0x85, 0xb7, 0x95, 0xaf, 0x71, 0xb1, 0xb5, 0xd9, 0xa0, 0xd0, 0xde, + 0xd8, 0xf1, 0x83, 0xaf, 0xc6, 0xf8, 0x8f, 0x94, 0x1d, 0xdb, 0x90, 0xfc, 0xc0, 0x00, 0xa0, 0xd0, + 0xde, 0xd8, 0xf4, 0x2d, 0x8e, 0xd8, 0xf1, 0x61, 0xd1, 0xaa, 0xd9, 0xde, 0xda, 0xf8, 0xd8, 0xf1, + 0xb1, 0x88, 0xbb, 0xa4, 0xd0, 0xc5, 0xa0, 0xd0, 0xc7, 0xb5, 0x90, 0xfc, 0xc2, 0x00, 0xd9, 0xb2, + 0x8e, 0xc6, 0xa4, 0xd0, 0xc5, 0xba, 0xae, 0xde, 0xf4, 0x2d, 0xbd, 0xd8, 0xf1, 0x84, 0xb4, 0x9f, + 0xba, 0xa7, 0x69, 0xda, 0xae, 0xf8, 0xf4, 0x2d, 0xbd, 0xd8, 0xf1, 0xae, 0xde, 0xd8, 0xf1, 0xb1, + 0x81, 0xb5, 0x9e, 0xbb, 0xaf, 0x02, 0xb7, 0x94, 0x26, 0xb3, 0x81, 0xb5, 0x9d, 0xa1, 0x02, 0xb7, + 0x90, 0x26, 0x8f, 0x91, 0xa1, 0x00, 0x2c, 0xb1, 0x80, 0x94, 0xaf, 0x12, 0x26, 0x5e, 0x6e, 0xb3, + 0x80, 0x92, 0xa2, 0x42, 0x0e, 0x76, 0x3e, 0x8f, 0xa2, 0x00, 0x2c, 0x54, 0x7c, 0xaf, 0xde, 0xf8, + 0xf5, 0x8f, 0x99, 0xaf, 0x06, 0xf1, 0x9f, 0xfc, 0xc1, 0x03, 0xd9, 0x8a, 0xaa, 0xc4, 0xd8, 0x83, + /* bank # 46 */ + 0x92, 0xaf, 0x51, 0xd9, 0xf4, 0x2e, 0x4b, 0xd8, 0xf1, 0xa2, 0xd0, 0xde, 0xb6, 0x9e, 0xfc, 0xc0, + 0x09, 0xdb, 0xfc, 0xc1, 0x0a, 0xd9, 0xb8, 0xae, 0xde, 0xba, 0xae, 0xde, 0xfa, 0xb7, 0xbb, 0xf4, + 0x2e, 0x4b, 0xd8, 0xf1, 0xb8, 0xae, 0xde, 0xf8, 0xba, 0xae, 0xdf, 0xf3, 0xbc, 0xbc, 0xbd, 0xbd, + 0xbe, 0xbe, 0xb0, 0xb4, 0xbb, 0xaf, 0xfb, 0xda, 0xb8, 0xa4, 0xd0, 0x8d, 0x94, 0x1d, 0xf1, 0xe2, + 0xd8, 0xf1, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xb3, 0xb7, 0xbb, 0xd8, 0xf1, 0x8a, 0x92, 0xaf, + 0x19, 0xd9, 0xf4, 0x2e, 0x8f, 0xd8, 0xf3, 0xbc, 0xbc, 0xb1, 0x8b, 0xc3, 0xbc, 0xbc, 0xb3, 0xf8, + 0xf9, 0xd1, 0xd9, 0xf4, 0x2e, 0x7d, 0xd8, 0xf1, 0x8e, 0x91, 0x41, 0xd9, 0xf4, 0x2e, 0x7d, 0xd8, + 0xf1, 0x89, 0x93, 0xa3, 0xc6, 0x60, 0x81, 0xa2, 0xd0, 0xc7, 0xf4, 0x2f, 0x0a, 0xd8, 0xf1, 0xa3, + 0xde, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0x8b, 0xaa, 0xc6, 0xf4, 0x2f, 0x0a, 0xd8, + 0xf1, 0x81, 0xaa, 0xc6, 0x9a, 0x60, 0x60, 0xb1, 0x81, 0xb5, 0x93, 0xaf, 0x59, 0xb3, 0xb7, 0xd1, + 0xd9, 0xf4, 0x2f, 0x0a, 0xd8, 0xf1, 0x8a, 0x92, 0xaf, 0x21, 0xda, 0xa3, 0xf8, 0xad, 0xde, 0xd8, + 0x81, 0xaa, 0xc5, 0x85, 0x91, 0xaf, 0x21, 0xd9, 0xf4, 0x2e, 0xe5, 0xd8, 0xf1, 0xa1, 0xdf, 0xa2, + 0xdf, 0xdf, 0x81, 0x95, 0xa5, 0xc7, 0x68, 0x89, 0x93, 0xa3, 0xc6, 0x60, 0xad, 0xf8, 0xaf, 0xde, + 0xf8, 0xf5, 0x89, 0x9f, 0x06, 0xf1, 0xfc, 0xc1, 0x03, 0xdb, 0x8d, 0x9d, 0xaf, 0x21, 0xa3, 0xde, + 0xf8, 0xd8, 0xf4, 0x2f, 0x0a, 0xd8, 0xf1, 0x81, 0xa5, 0xc5, 0x92, 0xaf, 0x49, 0xda, 0xa3, 0xf8, + 0xf8, 0xd8, 0x91, 0xaf, 0x49, 0xda, 0xa3, 0xf8, 0xf8, 0xf8, 0xf8, 0xd8, 0xf1, 0xa3, 0xf8, 0xf9, + /* bank # 47 */ + 0xd1, 0xd9, 0xb1, 0x83, 0xb9, 0xa1, 0xd0, 0xc6, 0xb3, 0xbb, 0xd8, 0xf5, 0x83, 0x9a, 0xaf, 0x1a, + 0xf1, 0xbe, 0xb8, 0xae, 0xc1, 0x89, 0xb5, 0x9e, 0x74, 0xfd, 0x3f, 0xbc, 0xbc, 0xb1, 0x8b, 0x34, + 0xb7, 0x9f, 0xfc, 0xc0, 0x00, 0xbc, 0xbc, 0xbc, 0xb0, 0xbd, 0xb4, 0xd9, 0xf4, 0x2f, 0x64, 0xd8, + 0xf1, 0xa6, 0xf8, 0x86, 0x96, 0xae, 0x11, 0xd9, 0xa6, 0xdf, 0x88, 0xbe, 0xbb, 0xa9, 0xd0, 0xc4, + 0xf2, 0xa1, 0xd0, 0xc6, 0xa2, 0xd0, 0xc6, 0xbe, 0xbe, 0xbe, 0xdb, 0xf1, 0x9e, 0xfc, 0xc3, 0x01, + 0xd9, 0xf2, 0xbe, 0xa1, 0xd0, 0xf8, 0xf8, 0xf8, 0xa2, 0xd0, 0xf8, 0xf8, 0xf8, 0xbe, 0xbe, 0xbe, + 0xd8, 0xf4, 0x2f, 0xa2, 0xd8, 0xf1, 0x9e, 0xfc, 0xc3, 0x01, 0xd9, 0xf5, 0x8e, 0xae, 0x32, 0xf1, + 0xdb, 0xfc, 0xc0, 0x01, 0x88, 0xbe, 0xbb, 0xa9, 0xd0, 0xc4, 0xf2, 0xa1, 0xd0, 0xc6, 0xa2, 0xd0, + 0xc6, 0xbe, 0xbe, 0xbe, 0xf4, 0x2f, 0xa2, 0xd8, 0xf1, 0xa6, 0xfa, 0x86, 0x96, 0xae, 0x39, 0xd9, + 0xa6, 0xde, 0x87, 0xbe, 0xbb, 0xa9, 0xd0, 0xc4, 0xf2, 0xa1, 0xd0, 0xc6, 0xa2, 0xd0, 0xc6, 0xbe, + 0xbe, 0xbe, 0xd8, 0xf1, 0xbc, 0xbc, 0xbc, 0xb3, 0xbd, 0xbd, 0xbd, 0xb7, 0xbe, 0xbe, 0xbe, 0xbb, + 0xa5, 0xf8, 0xf9, 0xd1, 0xda, 0x86, 0xa7, 0xc3, 0xc5, 0xc7, 0xa5, 0xde, 0x85, 0xa5, 0xd0, 0xc6, + 0xd8, 0x85, 0x95, 0xaf, 0x71, 0xda, 0xf4, 0x2f, 0xe2, 0xd8, 0xf1, 0x89, 0x93, 0xa3, 0x60, 0xf3, + 0xbe, 0xbe, 0xaf, 0xf8, 0xf9, 0xd1, 0xda, 0xf3, 0xe2, 0xd8, 0xf1, 0xbe, 0xbe, 0x86, 0xa7, 0xc3, + 0xc5, 0xc7, 0xd8, 0xf1, 0xaf, 0xdf, 0xf9, 0x89, 0x9f, 0x2d, 0x83, 0x0d, 0xf5, 0x99, 0xaf, 0x1a, + 0x8f, 0x7e, 0x9f, 0xa8, 0x12, 0x99, 0x2e, 0xf1, 0xdf, 0xdf, 0xaf, 0xdf, 0xf9, 0x89, 0x9f, 0x4d, + /* bank # 48 */ + 0x83, 0x0d, 0xf5, 0x9b, 0xaf, 0x02, 0x8f, 0x66, 0xf1, 0x9f, 0xfc, 0xc0, 0x03, 0xd9, 0xf5, 0xa8, + 0xd0, 0x12, 0x99, 0x36, 0xd8, 0xf1, 0x88, 0x98, 0xa6, 0x10, 0xa7, 0x38, 0x86, 0x9f, 0xaf, 0xde, + 0x00, 0xfd, 0x08, 0x87, 0x00, 0x8f, 0xf3, 0xae, 0xc0, 0xf1, 0xbc, 0xbc, 0xb1, 0x82, 0xc3, 0xbc, + 0xbc, 0xd8, 0xf3, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xbb, 0xb3, 0xb7, 0xa2, 0xf8, 0xf2, 0xf8, + 0xf1, 0x80, 0x9d, 0xad, 0xd0, 0x7c, 0xf2, 0xa2, 0xfa, 0xf9, 0xd1, 0xf1, 0xb9, 0xac, 0xd9, 0xde, + 0xda, 0xf8, 0xd8, 0xf5, 0xbe, 0xbe, 0xba, 0xa7, 0x85, 0x95, 0x78, 0x8e, 0x9e, 0x7c, 0xbc, 0xbc, + 0xbd, 0xbd, 0xb2, 0xb6, 0xf1, 0xa9, 0x89, 0x99, 0x62, 0xf0, 0x97, 0x40, 0x99, 0x6c, 0x97, 0x48, + 0xb9, 0xb1, 0xb5, 0xf1, 0xaf, 0x80, 0x91, 0x28, 0x8c, 0x9f, 0x00, 0x83, 0x65, 0xd9, 0xf4, 0x30, + 0x94, 0xd8, 0xf1, 0x9d, 0xfc, 0xc3, 0x04, 0xaf, 0xb2, 0x89, 0xd9, 0xc3, 0xc1, 0xda, 0xc1, 0xc3, + 0xd8, 0xf4, 0x75, 0x55, 0xd8, 0xf2, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xb9, 0xb3, 0xb7, 0xa6, + 0x81, 0x92, 0x49, 0xf9, 0xdb, 0xf1, 0xb1, 0x8c, 0xb5, 0x9c, 0x21, 0xd9, 0xf5, 0xb3, 0x85, 0xb7, + 0x95, 0x78, 0x8e, 0x9e, 0x7c, 0xf1, 0xb1, 0x8d, 0xb5, 0x9d, 0xad, 0x1a, 0xf0, 0x96, 0x40, 0x9d, + 0x3c, 0x96, 0x48, 0xd8, 0xf1, 0xb1, 0x81, 0xb5, 0x9d, 0xb9, 0xa6, 0x0a, 0x8d, 0x96, 0x05, 0xd9, + 0xf4, 0x30, 0xfb, 0xd8, 0xf2, 0xb3, 0x81, 0xb7, 0x92, 0xbb, 0xaf, 0x49, 0xf9, 0xf9, 0xdb, 0xf1, + 0xb1, 0x8c, 0xb5, 0x9c, 0xb9, 0xa6, 0x21, 0xf4, 0x30, 0xfb, 0xd8, 0xf1, 0xb3, 0x8e, 0xbb, 0xa8, + 0xd0, 0xc4, 0xc7, 0xf3, 0xb9, 0xac, 0xd0, 0xde, 0xf4, 0x31, 0x0c, 0xd8, 0xf1, 0xb3, 0x85, 0xbb, + /* bank # 49 */ + 0xa8, 0xd0, 0xc4, 0xc7, 0xf3, 0xb9, 0xac, 0xd0, 0xde, 0xf8, 0xdf, 0xf8, 0xd8, 0xf3, 0xb5, 0x9c, + 0xfc, 0xc3, 0x04, 0xdb, 0xfc, 0xc2, 0x00, 0xd9, 0xf2, 0xac, 0xd0, 0xde, 0xd8, 0xf2, 0xbb, 0xaf, + 0xb7, 0x92, 0xb3, 0x82, 0x19, 0xdb, 0xa2, 0xdf, 0xa1, 0xd0, 0xc4, 0xac, 0xd0, 0xc5, 0xf3, 0xa7, + 0xd0, 0xdf, 0xf1, 0xb9, 0xaa, 0xde, 0xa1, 0xdf, 0xb5, 0x9b, 0xfc, 0xc1, 0x00, 0xb8, 0xbe, 0xa7, + 0xd0, 0xde, 0xbe, 0xbe, 0xbe, 0xd8, 0xf1, 0xbb, 0xaf, 0x89, 0xb7, 0x98, 0x19, 0xa9, 0x80, 0xd9, + 0x38, 0xd8, 0xaf, 0x89, 0x39, 0xa9, 0x80, 0xda, 0x3c, 0xd8, 0xa1, 0xf8, 0xf9, 0xd1, 0xda, 0xf9, + 0xdf, 0xf8, 0xf4, 0x75, 0x3d, 0xf1, 0xff, 0xd8, 0xaf, 0x2e, 0x88, 0xf5, 0x75, 0xda, 0xff, 0xd8, + 0x71, 0xda, 0xf1, 0xff, 0xd8, 0x82, 0xa7, 0xf3, 0xc1, 0xf2, 0x80, 0xc2, 0xf1, 0x97, 0x86, 0x49, + 0x2e, 0xa6, 0xd0, 0x50, 0x96, 0x86, 0xaf, 0x75, 0xd9, 0x88, 0xa2, 0xd0, 0xf3, 0xc0, 0xc3, 0xf1, + 0xda, 0x8f, 0x96, 0xa2, 0xd0, 0xf3, 0xc2, 0xc3, 0x82, 0xb6, 0x9b, 0x70, 0x70, 0xf1, 0xd8, 0xb7, + 0xaf, 0xdf, 0xf9, 0x89, 0x99, 0xaf, 0x10, 0x80, 0x9f, 0x21, 0xda, 0x2e, 0xd8, 0x89, 0x99, 0xaf, + 0x31, 0xda, 0xdf, 0xd8, 0xaf, 0x82, 0x92, 0xf3, 0x41, 0xd9, 0xf1, 0xdf, 0xd8, 0xaf, 0x82, 0xf3, + 0x19, 0xd9, 0xf1, 0xdf, 0xd8, 0xf1, 0x89, 0x90, 0xaf, 0xd0, 0x09, 0x8f, 0x99, 0xaf, 0x51, 0xdb, + 0x89, 0x31, 0xf3, 0x82, 0x92, 0x19, 0xf2, 0xb1, 0x8c, 0xb5, 0x9c, 0x71, 0xd9, 0xf1, 0xdf, 0xf9, + 0xf2, 0xb9, 0xac, 0xd0, 0xf8, 0xf8, 0xf3, 0xdf, 0xd8, 0xb3, 0xb7, 0xbb, 0x82, 0xac, 0xf3, 0xc0, + 0xa2, 0x80, 0x22, 0xf1, 0xa9, 0x22, 0x26, 0x9f, 0xaf, 0x29, 0xda, 0xac, 0xde, 0xff, 0xd8, 0xa2, + /* bank # 50 */ + 0xf2, 0xde, 0xf1, 0xa9, 0xdf, 0xf2, 0x82, 0xb8, 0xbe, 0xa9, 0xc3, 0x81, 0xc5, 0xb0, 0xbc, 0xf1, + 0xb5, 0x9b, 0xfc, 0xc1, 0x03, 0xb4, 0xbd, 0xd9, 0xf4, 0x32, 0x33, 0xd8, 0xf2, 0x89, 0x99, 0xa9, + 0x49, 0xda, 0xf4, 0x32, 0x33, 0xd8, 0xf1, 0x9a, 0xfc, 0xc0, 0x04, 0xa7, 0xd0, 0xd9, 0x88, 0x97, + 0x30, 0xda, 0xde, 0xd8, 0xf1, 0xbc, 0xb1, 0x80, 0xbb, 0xbe, 0xbe, 0xbe, 0xaf, 0xc2, 0x8c, 0xc1, + 0x81, 0xc3, 0x83, 0xc7, 0xbc, 0xbc, 0xb3, 0x8f, 0xb7, 0xbd, 0xbd, 0xbd, 0x9f, 0xba, 0xa7, 0x61, + 0xdb, 0x69, 0x71, 0xff, 0xd8, 0xf1, 0xbb, 0xad, 0xd0, 0xde, 0xf8, 0xb1, 0x84, 0xb6, 0x96, 0xba, + 0xa7, 0xd0, 0x7e, 0xb7, 0x96, 0xa7, 0x01, 0xb2, 0x87, 0x9d, 0x05, 0xdb, 0xb3, 0x8d, 0xb6, 0x97, + 0x79, 0xf3, 0xb1, 0x8c, 0x96, 0x49, 0xf1, 0xbb, 0xad, 0xd0, 0xf8, 0xd8, 0xf3, 0xb9, 0xac, 0xd0, + 0xf8, 0xf9, 0xd1, 0xd9, 0xf1, 0xbb, 0xad, 0xd0, 0xf8, 0xd8, 0xb3, 0xb7, 0xbb, 0x97, 0x8c, 0xaf, + 0xf3, 0x79, 0xd9, 0xf4, 0x32, 0xa6, 0xd8, 0xf1, 0xa1, 0x81, 0x9d, 0x34, 0xaa, 0xd0, 0x8a, 0x50, + 0xf4, 0x75, 0x3d, 0xf4, 0x32, 0xc6, 0xd8, 0xf3, 0xa7, 0xd0, 0xfa, 0xb5, 0x9c, 0xfc, 0xc2, 0x07, + 0xd9, 0xf8, 0xd8, 0xb7, 0x97, 0x8c, 0xaf, 0x79, 0xda, 0xf1, 0x87, 0x91, 0xa1, 0x6c, 0xaa, 0xd0, + 0x9a, 0x70, 0xbb, 0xf4, 0x75, 0x3d, 0xd8, 0xf1, 0x91, 0xfc, 0xc1, 0x0a, 0xd9, 0xf4, 0x33, 0x07, + 0xd8, 0xf1, 0x81, 0xa1, 0xc2, 0xf9, 0xdf, 0xf8, 0x80, 0x9d, 0xba, 0xa6, 0xd0, 0x38, 0xfd, 0x31, + 0xbb, 0xaf, 0xde, 0xf3, 0x82, 0xce, 0xf1, 0x8f, 0x90, 0x08, 0xfd, 0x0f, 0x8d, 0x9f, 0x65, 0xd9, + 0xf4, 0x33, 0x07, 0xd8, 0xf1, 0xaf, 0xde, 0xf2, 0x8c, 0xce, 0xf2, 0x82, 0x9f, 0x25, 0xd9, 0xf1, + /* bank # 51 */ + 0xba, 0xa6, 0xd0, 0xde, 0xf3, 0x8d, 0xce, 0xd8, 0xf1, 0xb5, 0x9b, 0xfc, 0xc1, 0x03, 0xd9, 0xbc, + 0xbd, 0xbe, 0xf4, 0x33, 0x3b, 0xd8, 0xf1, 0xb8, 0xbe, 0xaa, 0xd0, 0xde, 0xf2, 0xb3, 0x81, 0xb7, + 0x92, 0xa9, 0x49, 0xd9, 0xbc, 0xbd, 0xf4, 0x33, 0x3b, 0xd8, 0xf1, 0xbc, 0xbd, 0xb0, 0xb4, 0x8d, + 0x97, 0x31, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xd9, 0xaa, 0xd0, 0xf8, 0xd8, 0xf1, 0xbc, 0xbc, 0xbd, + 0xbd, 0xbe, 0xbe, 0xb0, 0x84, 0xb8, 0xa5, 0xc3, 0xc5, 0xc7, 0x83, 0xa4, 0xc3, 0xc5, 0xc7, 0xf0, + 0xb2, 0x81, 0xb6, 0x91, 0xa3, 0x3c, 0x11, 0x0c, 0x58, 0x2c, 0x50, 0xf1, 0xb0, 0x83, 0xb4, 0x93, + 0xa3, 0x2c, 0x54, 0x7c, 0x92, 0x71, 0xf0, 0x95, 0xae, 0x2c, 0x50, 0x78, 0x8e, 0xbe, 0xb9, 0xaa, + 0xc2, 0xbc, 0xbd, 0xd8, 0xf2, 0xbb, 0xb3, 0xb7, 0x82, 0x91, 0xaf, 0x31, 0xda, 0xf4, 0x33, 0xdf, + 0xd8, 0xf1, 0x8d, 0xb7, 0x96, 0xbb, 0xa6, 0x40, 0xac, 0x8c, 0x9c, 0x0c, 0x30, 0xba, 0x8d, 0x9d, + 0xa7, 0x39, 0xdb, 0xf3, 0xb1, 0x8c, 0xb6, 0x96, 0x49, 0xd9, 0xf1, 0x84, 0xb5, 0x94, 0xb9, 0xa4, + 0xd0, 0x5e, 0xf0, 0xb7, 0x9d, 0x38, 0xd8, 0xf1, 0xb3, 0x8d, 0xba, 0xa7, 0xc6, 0xb5, 0x9c, 0xfc, + 0xc2, 0x04, 0xd9, 0xb1, 0x81, 0xb6, 0x97, 0xa7, 0x25, 0x8b, 0x6e, 0x81, 0xb9, 0xa1, 0x34, 0xda, + 0xb2, 0x87, 0xb6, 0x97, 0x00, 0xfd, 0x3e, 0xb1, 0x81, 0x25, 0x8b, 0x4e, 0x81, 0xb9, 0xa1, 0x34, + 0xd8, 0xf1, 0xbb, 0xaa, 0xd0, 0xdf, 0xac, 0xde, 0xd0, 0xde, 0xad, 0xd0, 0xdf, 0xf1, 0xff, 0xd8, + 0xf2, 0xb3, 0xb7, 0xaf, 0x82, 0x9c, 0x39, 0xdb, 0xf1, 0x86, 0x90, 0x09, 0xaa, 0xd0, 0x8a, 0x9d, + 0xd9, 0x74, 0xf4, 0x33, 0xfa, 0xda, 0xf1, 0xaa, 0xd0, 0xdf, 0xd8, 0xf3, 0xb9, 0xac, 0xd0, 0xf8, + /* bank # 52 */ + 0xf9, 0xd1, 0xd9, 0xf2, 0xbb, 0xa2, 0xfa, 0xf8, 0xda, 0xf2, 0xbb, 0xa2, 0xfa, 0xd8, 0xf2, 0xb3, + 0x82, 0xb6, 0x9b, 0xbb, 0xaf, 0x31, 0xdb, 0xf1, 0x89, 0xb5, 0x9a, 0x61, 0xd9, 0xf2, 0xa1, 0xd0, + 0xf8, 0xf8, 0xd8, 0xf2, 0x82, 0xaf, 0xc4, 0xf8, 0xf8, 0xf8, 0xf8, 0x8f, 0xb7, 0x91, 0x15, 0xda, + 0xa1, 0xd0, 0xc0, 0xd8, 0x82, 0xaf, 0xc2, 0xf9, 0xd1, 0xd9, 0xf1, 0xb9, 0xac, 0xde, 0xad, 0xde, + 0xdf, 0xb9, 0xa1, 0xdf, 0xbb, 0xad, 0xd0, 0xdf, 0xd8, 0xf2, 0x82, 0x91, 0xaf, 0x31, 0xda, 0xf1, + 0xb1, 0x81, 0x9d, 0xb9, 0xa1, 0x3c, 0xd8, 0xf2, 0xb3, 0xbb, 0x82, 0x91, 0xaf, 0x31, 0xd1, 0xd9, + 0xf1, 0xb1, 0x81, 0xb5, 0x9b, 0xb9, 0xa1, 0x3e, 0xd8, 0xf1, 0xb3, 0x8c, 0xb7, 0x9c, 0xbb, 0xac, + 0xd0, 0x10, 0xac, 0xde, 0xad, 0xd0, 0xdf, 0x92, 0x82, 0xaf, 0xf1, 0xca, 0xf2, 0x91, 0x35, 0xf1, + 0x96, 0x8f, 0xa6, 0xd9, 0x00, 0xdb, 0xaf, 0x8a, 0x90, 0x6d, 0xd9, 0xa6, 0x8f, 0x96, 0x01, 0x8a, + 0x60, 0xaa, 0xd0, 0xdf, 0xf2, 0x81, 0xac, 0xd0, 0xc5, 0xd8, 0xf1, 0xff, 0xd8, 0xf0, 0xb9, 0xb1, + 0xb6, 0xaf, 0x8d, 0x92, 0x4c, 0x71, 0x54, 0x68, 0x5c, 0x60, 0x44, 0x79, 0xe0, 0xd8, 0xf1, 0xba, + 0xb1, 0xa4, 0x8f, 0xc0, 0xc3, 0xc5, 0xc7, 0xb9, 0xb5, 0xf1, 0xaa, 0x82, 0x90, 0x25, 0xf3, 0xad, + 0xdf, 0xd9, 0xf8, 0xf8, 0xd8, 0xf1, 0xa1, 0x81, 0x91, 0xf0, 0x34, 0x82, 0x38, 0xf1, 0xaa, 0x2d, + 0xf5, 0x8a, 0x90, 0x30, 0xd9, 0xf3, 0xad, 0xfa, 0xd8, 0xf0, 0xaa, 0x8f, 0x9f, 0x04, 0x28, 0x51, + 0x79, 0x1d, 0x30, 0x14, 0x38, 0xbc, 0xbc, 0xbc, 0xa2, 0xd0, 0x8a, 0x9a, 0x2c, 0x50, 0x50, 0x78, + 0x78, 0xbc, 0x82, 0x90, 0xaa, 0xf5, 0x7c, 0xf3, 0xd9, 0xad, 0xfa, 0xd8, 0xf1, 0xb8, 0xae, 0x82, + /* bank # 53 */ + 0xc6, 0xb9, 0xa1, 0x81, 0x90, 0x0a, 0x81, 0x92, 0x18, 0xa2, 0xd0, 0x81, 0xc1, 0xf3, 0xad, 0xfb, + 0xf9, 0xf1, 0xda, 0xa2, 0xd0, 0xdf, 0xd8, 0xa2, 0xd0, 0xfa, 0xf9, 0xd1, 0xda, 0xaa, 0x82, 0x9d, + 0x7e, 0x76, 0xad, 0x8a, 0xd0, 0x31, 0x5c, 0xf0, 0xaa, 0x8d, 0x9d, 0x54, 0x78, 0xfd, 0x7f, 0xf1, + 0x8a, 0x92, 0x55, 0x9d, 0xad, 0xd0, 0x72, 0x7e, 0xd8, 0xf4, 0x74, 0x9c, 0xe0, 0xd8, 0xf1, 0xb1, + 0xb9, 0x82, 0xa2, 0xd0, 0xc2, 0xf2, 0xa3, 0xfa, 0xf3, 0xb8, 0xa7, 0xf8, 0xf9, 0xd1, 0xda, 0xf2, + 0xe2, 0xd8, 0xbb, 0xb3, 0xe0, 0xf1, 0xb1, 0xaf, 0x8f, 0x9f, 0x31, 0x85, 0xa5, 0xd0, 0xda, 0xc6, + 0xf4, 0x35, 0x72, 0xd8, 0xf1, 0xf8, 0xf9, 0xd1, 0xd9, 0xc6, 0xf5, 0xad, 0xd0, 0x8d, 0x9e, 0x7f, + 0xda, 0xf9, 0xd8, 0xf1, 0xe0, 0xf1, 0xb6, 0x97, 0xa7, 0x66, 0xb7, 0x93, 0xf0, 0x71, 0x71, 0x60, + 0xe0, 0xf0, 0x01, 0x29, 0x51, 0x79, 0xe0, 0xf1, 0xc2, 0xc5, 0xc7, 0xb2, 0x87, 0xb6, 0x97, 0x2c, + 0xfd, 0x01, 0xe0, 0xf1, 0xc2, 0xc5, 0xc7, 0xb2, 0x87, 0xc1, 0xe0, 0xf1, 0xb2, 0x81, 0x97, 0x66, + 0xe0, 0xf0, 0x38, 0x10, 0x28, 0x40, 0x88, 0xe0, 0xf0, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38, 0x64, + 0x48, 0x31, 0x2d, 0x51, 0x79, 0xe0, 0xf0, 0x24, 0x58, 0x3d, 0x40, 0x34, 0x49, 0x2d, 0x51, 0xe0, + 0xf1, 0x87, 0xa1, 0x00, 0x2c, 0x54, 0x7c, 0xf0, 0x81, 0xa7, 0x04, 0x28, 0x50, 0x78, 0xfd, 0x7f, + 0xf1, 0xa7, 0x87, 0x96, 0x59, 0x91, 0xa1, 0x02, 0x0e, 0x16, 0x1e, 0xe0, 0xd8, 0xf0, 0xbe, 0xbe, + 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xb3, 0xbb, 0x8c, 0xac, 0xf4, 0x78, 0x59, 0x8d, 0xad, + 0xf4, 0x78, 0x59, 0x8e, 0xae, 0xf4, 0x78, 0x59, 0xbc, 0xb0, 0x80, 0xba, 0xaf, 0xf1, 0xde, 0xdf, + /* bank # 54 */ + 0xdf, 0xd0, 0xf2, 0xc2, 0xcb, 0xc5, 0xbc, 0xbc, 0xbc, 0xb2, 0x8f, 0xd0, 0xbd, 0xb5, 0x9e, 0xf1, + 0x02, 0xfd, 0x03, 0x26, 0xfd, 0x03, 0x46, 0xfd, 0x03, 0xbd, 0xbd, 0xbd, 0xb5, 0x90, 0xbb, 0xaf, + 0x02, 0xf0, 0x28, 0x50, 0xf1, 0x1e, 0x91, 0xf0, 0x20, 0x48, 0xf1, 0x16, 0xf0, 0x38, 0x92, 0x40, + 0xb3, 0xb7, 0x8f, 0xf2, 0xac, 0xc0, 0xad, 0xc2, 0xae, 0xc4, 0xf1, 0xa9, 0xfa, 0xf9, 0xd1, 0xd9, + 0xf4, 0x36, 0x4a, 0xd8, 0xf1, 0xa9, 0xfa, 0xf4, 0x38, 0x1c, 0xd8, 0xf0, 0xb7, 0x8c, 0x9c, 0xba, + 0xf4, 0x78, 0x28, 0xf1, 0xc1, 0xb3, 0x8d, 0x9d, 0xba, 0xf4, 0x78, 0x28, 0xf1, 0x1c, 0xb3, 0x8e, + 0x9e, 0xba, 0xf4, 0x78, 0x28, 0xf1, 0x1c, 0xb3, 0x8f, 0xd7, 0xfd, 0x3e, 0xf2, 0x8d, 0xc1, 0x8e, + 0xc1, 0xf1, 0x8f, 0xd5, 0xfd, 0x30, 0xd4, 0xd0, 0xfd, 0x70, 0xf1, 0xd0, 0x2a, 0xd2, 0xf0, 0x00, + 0xd2, 0xa9, 0xde, 0x8f, 0xb5, 0x97, 0xaf, 0xf5, 0x40, 0xd9, 0xf2, 0xa9, 0xf8, 0xd8, 0x97, 0xaf, + 0xf5, 0x48, 0xd9, 0xf3, 0xa9, 0xf8, 0xd8, 0xf2, 0xaf, 0xde, 0xf8, 0xd4, 0xfd, 0x0c, 0xb7, 0x8f, + 0x9d, 0x05, 0xda, 0xf4, 0x36, 0xc3, 0xd8, 0xf2, 0xb5, 0x97, 0xde, 0xf8, 0xd0, 0x37, 0xfd, 0x0e, + 0x3f, 0xfd, 0x0e, 0x8d, 0xb7, 0x9f, 0xd0, 0x05, 0xd9, 0xa9, 0xf8, 0xd8, 0xaf, 0x0d, 0xd9, 0xa9, + 0xf3, 0xf8, 0xd8, 0xd8, 0xf2, 0xaf, 0xde, 0xf8, 0xd4, 0xfd, 0x0c, 0x8f, 0x9e, 0x05, 0xda, 0xf4, + 0x36, 0xee, 0xd8, 0xf2, 0xb5, 0x97, 0xde, 0xf8, 0xd0, 0x37, 0xfd, 0x0e, 0x3f, 0xfd, 0x0e, 0x8e, + 0xb7, 0x9f, 0xd0, 0x05, 0xd9, 0xa9, 0xf8, 0xd8, 0xaf, 0x0d, 0xd9, 0xa9, 0xf3, 0xf8, 0xd8, 0xf1, + 0x8c, 0xaf, 0xde, 0xf2, 0xc0, 0x8f, 0xf0, 0xd4, 0xfd, 0x30, 0x9f, 0xf5, 0x00, 0xb1, 0x88, 0x04, + /* bank # 55 */ + 0xd9, 0xa9, 0xf2, 0xf8, 0xd8, 0xf5, 0xaf, 0x24, 0xd9, 0xa9, 0xf3, 0xf8, 0xd8, 0xf0, 0xaf, 0xb3, + 0x89, 0xc4, 0xc7, 0x8f, 0xd0, 0xd4, 0xfd, 0x40, 0xd5, 0xfd, 0x40, 0xb1, 0x88, 0xd0, 0xf5, 0x44, + 0xd9, 0xa9, 0xf2, 0xf8, 0xd8, 0xaf, 0xf5, 0x6c, 0xd9, 0xa9, 0xf3, 0xf8, 0xd8, 0xb3, 0x8f, 0xb5, + 0x99, 0xf5, 0xaf, 0x60, 0xd9, 0xaa, 0xf8, 0xf4, 0x37, 0x45, 0xd8, 0xf1, 0xb1, 0x8a, 0xb7, 0x9f, + 0xaf, 0x59, 0xd9, 0xaa, 0xde, 0xd8, 0xf5, 0xb3, 0x8f, 0xb5, 0x99, 0xaf, 0x68, 0xd9, 0xaa, 0xfa, + 0xda, 0xaa, 0xdf, 0xd8, 0xf1, 0x8a, 0xaf, 0xd4, 0xfd, 0x00, 0xd5, 0xfd, 0x40, 0x8f, 0xd0, 0xf5, + 0x14, 0xa9, 0xd0, 0xd9, 0xde, 0xda, 0xf8, 0xd8, 0xaf, 0x3c, 0xa9, 0xd0, 0xd9, 0xdf, 0xda, 0xfa, + 0xd8, 0xf1, 0x8a, 0xaf, 0xd6, 0xfd, 0x00, 0xd7, 0xfd, 0x40, 0x8f, 0x9a, 0xd0, 0xf5, 0x04, 0xa9, + 0xd9, 0xf2, 0xf8, 0xd8, 0xaf, 0xf5, 0x2c, 0xa9, 0xd9, 0xf3, 0xf8, 0xd8, 0x8c, 0xaf, 0xf2, 0xc0, + 0xf1, 0x8f, 0xd4, 0xfd, 0x30, 0xb7, 0x9f, 0x02, 0xfd, 0x1e, 0xd0, 0x10, 0xaf, 0xde, 0xf8, 0xf8, + 0xf8, 0xf8, 0xf8, 0xf8, 0xbd, 0xbd, 0xbd, 0x93, 0xf5, 0x02, 0xf1, 0xbd, 0xf8, 0xf9, 0xd1, 0xda, + 0xf4, 0x37, 0xbd, 0xd8, 0xf1, 0xb1, 0x8a, 0x9f, 0x59, 0xda, 0xf4, 0x37, 0xd3, 0xd8, 0xf1, 0xb1, + 0x8b, 0x9f, 0xaf, 0x51, 0xda, 0xf4, 0x37, 0xd3, 0xd8, 0xf1, 0xb5, 0x9b, 0xb3, 0x8f, 0x41, 0xd9, + 0xa9, 0xf2, 0xf8, 0xd8, 0xf1, 0xaf, 0xb7, 0x9f, 0xb1, 0x8a, 0x79, 0xda, 0xf4, 0x37, 0xf2, 0xd8, + 0xf1, 0x8b, 0x71, 0xda, 0xf4, 0x37, 0xf2, 0xd8, 0xf1, 0xb5, 0x9b, 0xb3, 0x8f, 0x49, 0xd9, 0xa9, + 0xf3, 0xf8, 0xd8, 0xf0, 0xa9, 0xf2, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xaa, 0xd0, 0xf0, + /* bank # 56 */ + 0xda, 0xde, 0xf5, 0xe2, 0xf0, 0xd9, 0xf8, 0xd8, 0xa9, 0xf3, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, + 0xf9, 0xaa, 0xd0, 0xf0, 0xda, 0xdf, 0xf6, 0xe2, 0xf0, 0xd9, 0xfa, 0xd8, 0xd8, 0xf0, 0xbc, 0xb0, + 0x80, 0xbd, 0xb4, 0x90, 0xbe, 0xb8, 0xa0, 0xe0, 0xf0, 0xaf, 0xf2, 0x11, 0x3d, 0xf3, 0x15, 0x3d, + 0xf2, 0xb2, 0x8f, 0xd0, 0xcd, 0xcf, 0xf3, 0xdf, 0xdf, 0xdf, 0xdf, 0xf1, 0xd4, 0xfd, 0x70, 0xd5, + 0xfd, 0x70, 0xd6, 0xfd, 0x70, 0xd7, 0xfd, 0x70, 0xb6, 0x9f, 0x0c, 0x10, 0x18, 0xf5, 0x00, 0xb5, + 0x96, 0xf5, 0x18, 0xbb, 0xaf, 0xd0, 0xb7, 0x9f, 0xe0, 0xf0, 0xd0, 0xf3, 0xcf, 0xf2, 0xcc, 0xd0, + 0xf3, 0xcd, 0xf2, 0xca, 0xd0, 0xf3, 0xcb, 0xf2, 0xc8, 0xd0, 0xf3, 0xc9, 0xe0 \ No newline at end of file